diff --git a/.gitignore b/.gitignore
index cf27052c2dae133737281ae881a25d658c199d59..a8991d7ec6859433b50905c62f4b18bb532a6ae9 100644
--- a/.gitignore
+++ b/.gitignore
@@ -17,6 +17,8 @@ build
 /Tools/ArdupilotMegaPlanner/obj
 /Tools/ArdupilotMegaPlanner/resedit/bin
 /Tools/ArdupilotMegaPlanner/resedit/obj
+/Tools/ArdupilotMegaPlanner/wix/bin
+/Tools/ArdupilotMegaPlanner/wix/obj
 tags
 *.o
 .*.swp
@@ -24,3 +26,5 @@ tags
 mav.log
 mav.log.raw
 status.txt
+
+/Tools/ArdupilotMegaPlanner/Msi/upload.bat
\ No newline at end of file
diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde
index 5d12c30de331cfa6bd3f4a0c05cfa2034f378ca5..d88fa06061ef80050015b447e77db7a135dfa680 100644
--- a/ArduCopter/ArduCopter.pde
+++ b/ArduCopter/ArduCopter.pde
@@ -77,6 +77,15 @@ http://code.google.com/p/ardupilot-mega/downloads/list
 #include <APM_PI.h>            	// PI library
 #include <AC_PID.h>            // PID library
 #include <RC_Channel.h>     // RC Channel Library
+#include <AP_Motors.h>		// AP Motors library
+#include <AP_MotorsQuad.h>	// AP Motors library for Quad
+#include <AP_MotorsTri.h>	// AP Motors library for Tri
+#include <AP_MotorsHexa.h>	// AP Motors library for Hexa
+#include <AP_MotorsY6.h>	// AP Motors library for Y6
+#include <AP_MotorsOcta.h>	// AP Motors library for Octa
+#include <AP_MotorsOctaQuad.h>	// AP Motors library for OctaQuad
+#include <AP_MotorsHeli.h>	// AP Motors library for Heli
+#include <AP_MotorsMatrix.h>	// AP Motors library for Heli
 #include <AP_RangeFinder.h>	// Range finder library
 #include <AP_OpticalFlow.h> // Optical Flow library
 #include <Filter.h>			// Filter library
@@ -362,11 +371,46 @@ static byte 	old_control_mode = STABILIZE;
 // Motor Output
 ////////////////////////////////////////////////////////////////////////////////
 // This is the array of PWM values being sent to the motors
-static int16_t  motor_out[11];
+//static int16_t  motor_out[11];
 // This is the array of PWM values being sent to the motors that has been lightly filtered with a simple LPF
 // This was added to try and deal with biger motors
-static int16_t  motor_filtered[11];
+//static int16_t  motor_filtered[11];
 
+#if FRAME_CONFIG ==	QUAD_FRAME
+	#define MOTOR_CLASS AP_MotorsQuad
+#endif
+#if FRAME_CONFIG ==	TRI_FRAME
+	#define MOTOR_CLASS AP_MotorsTri
+#endif
+#if FRAME_CONFIG ==	HEXA_FRAME
+	#define MOTOR_CLASS AP_MotorsHexa
+#endif
+#if FRAME_CONFIG ==	Y6_FRAME
+	#define MOTOR_CLASS AP_MotorsY6
+#endif
+#if FRAME_CONFIG ==	OCTA_FRAME
+	#define MOTOR_CLASS AP_MotorsOcta
+#endif
+#if FRAME_CONFIG ==	OCTA_QUAD_FRAME
+	#define MOTOR_CLASS AP_MotorsOctaQuad
+#endif
+#if FRAME_CONFIG ==	HELI_FRAME
+	#define MOTOR_CLASS AP_MotorsHeli
+#endif
+
+#if FRAME_CONFIG ==	HELI_FRAME  // helicopter constructor requires more arguments
+	#if INSTANT_PWM == 1
+		MOTOR_CLASS	motors(CONFIG_APM_HARDWARE, &APM_RC, &g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, &g.heli_servo_1, &g.heli_servo_2, &g.heli_servo_3, &g.heli_servo_4, AP_MOTORS_SPEED_INSTANT_PWM);   // this hardware definition is slightly bad because it assumes APM_HARDWARE_APM2 == AP_MOTORS_APM2
+	#else
+		MOTOR_CLASS	motors(CONFIG_APM_HARDWARE, &APM_RC, &g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, &g.heli_servo_1, &g.heli_servo_2, &g.heli_servo_3, &g.heli_servo_4);
+	#endif
+#else
+	#if INSTANT_PWM == 1
+		MOTOR_CLASS	motors(CONFIG_APM_HARDWARE, &APM_RC, &g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, AP_MOTORS_SPEED_INSTANT_PWM);   // this hardware definition is slightly bad because it assumes APM_HARDWARE_APM2 == AP_MOTORS_APM2
+	#else
+		MOTOR_CLASS	motors(CONFIG_APM_HARDWARE, &APM_RC, &g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4);
+	#endif
+#endif
 
 ////////////////////////////////////////////////////////////////////////////////
 // Mavlink/HIL control
@@ -379,30 +423,12 @@ static bool rc_override_active = false;
 // Status flag that tracks whether we are under GCS control
 static uint32_t rc_override_fs_timer = 0;
 
-////////////////////////////////////////////////////////////////////////////////
-// Heli
-////////////////////////////////////////////////////////////////////////////////
-#if FRAME_CONFIG ==	HELI_FRAME
-static float heli_rollFactor[3], heli_pitchFactor[3], heli_collectiveFactor[3];	// only required for 3 swashplate servos
-static int16_t heli_servo_min[3], heli_servo_max[3];							// same here.  for yaw servo we use heli_servo4_min/max parameter directly
-static int32_t heli_servo_out[4];												// used for servo averaging for analog servos
-static int16_t heli_servo_out_count;											// use for servo averaging
-#endif
-
 ////////////////////////////////////////////////////////////////////////////////
 // Failsafe
 ////////////////////////////////////////////////////////////////////////////////
 // A status flag for the failsafe state
 // did our throttle dip below the failsafe value?
 static boolean 	failsafe;
-// A status flag for arming the motors. This is the arming that is performed when the
-// Yaw control is held right or left while throttle is low.
-static boolean	motor_armed;
-// A status flag for whether or not we should allow AP to take over copter
-// This is tied to the throttle. If the throttle = 0 or low/nuetral, then we do not allow
-// the APM to take control of the copter.
-static boolean	motor_auto_armed;
-
 
 ////////////////////////////////////////////////////////////////////////////////
 // PIDs
@@ -948,9 +974,6 @@ static void fast_loop()
 	// ------------------------------
 	set_servos_4();
 
-	//if(motor_armed)
-		//Log_Write_Attitude();
-
 	// agmatthews - USERHOOKS
 	#ifdef USERHOOK_FASTLOOP
 	   USERHOOK_FASTLOOP
@@ -1026,7 +1049,7 @@ static void medium_loop()
 					// -----------------------------
 					update_navigation();
 
-					if (g.log_bitmask & MASK_LOG_NTUN && motor_armed){
+					if (g.log_bitmask & MASK_LOG_NTUN && motors.armed()){
 						Log_Write_Nav_Tuning();
 					}
 				}
@@ -1060,7 +1083,7 @@ static void medium_loop()
 				}
 			}
 
-            if(motor_armed){
+            if(motors.armed()){
                 if (g.log_bitmask & MASK_LOG_ATTITUDE_MED)
                     Log_Write_Attitude();
 
@@ -1149,22 +1172,16 @@ static void fifty_hz_loop()
 	camera_stabilization();
 
 	# if HIL_MODE == HIL_MODE_DISABLED
-		if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST && motor_armed)
+		if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST && motors.armed())
 			Log_Write_Attitude();
 
-		if (g.log_bitmask & MASK_LOG_RAW && motor_armed)
+		if (g.log_bitmask & MASK_LOG_RAW && motors.armed())
 			Log_Write_Raw();
 	#endif
 
 	// kick the GCS to process uplink data
 	gcs_update();
     gcs_data_stream_send();
-
-	#if FRAME_CONFIG == TRI_FRAME
-		// servo Yaw
-		g.rc_4.calc_pwm();
-		APM_RC.OutputCh(CH_TRI_YAW, g.rc_4.radio_out);
-	#endif
 }
 
 
@@ -1190,6 +1207,12 @@ static void slow_loop()
 					}
 				#endif
             }
+
+			// check the user hasn't updated the frame orientation
+			if( !motors.armed() ) {
+				motors.set_frame_orientation(g.frame_orientation);
+			}
+
 			break;
 
 		case 1:
@@ -1235,7 +1258,7 @@ static void slow_loop()
 // 1Hz loop
 static void super_slow_loop()
 {
-	if (g.log_bitmask & MASK_LOG_CUR && motor_armed)
+	if (g.log_bitmask & MASK_LOG_CUR && motors.armed())
 		Log_Write_Current();
 
 	// this function disarms the copter if it has been sitting on the ground for any moment of time greater than 30s
@@ -1381,7 +1404,7 @@ static void update_GPS(void)
 		current_loc.lng = g_gps->longitude;	// Lon * 10 * *7
 		current_loc.lat = g_gps->latitude;	// Lat * 10 * *7
 
-		if (g.log_bitmask & MASK_LOG_GPS && motor_armed){
+		if (g.log_bitmask & MASK_LOG_GPS && motors.armed()){
 			Log_Write_GPS();
 		}
 
@@ -1664,7 +1687,8 @@ void update_throttle_mode(void)
 					update_throttle_cruise();
 				}
 
-				if(motor_auto_armed == true){
+				// 10hz, 			don't run up i term
+				if( motors.auto_armed() == true ){
 
 					// how far off are we
 					altitude_error = get_altitude_error();
@@ -1972,7 +1996,7 @@ static void update_altitude_est()
 		update_altitude();
 		alt_sensor_flag = false;
 
-		if(g.log_bitmask & MASK_LOG_CTUN && motor_armed){
+		if(g.log_bitmask & MASK_LOG_CTUN && motors.armed()){
 			Log_Write_Control_Tuning();
 		}
 
@@ -2067,7 +2091,7 @@ static void tuning(){
 			break;
 
 		case CH6_TOP_BOTTOM_RATIO:
-			g.top_bottom_ratio = tuning_value;
+			motors.top_bottom_ratio = tuning_value;
 			break;
 
 		case CH6_RELAY:
@@ -2116,7 +2140,7 @@ static void tuning(){
 
 		#if FRAME_CONFIG == HELI_FRAME
 		case CH6_HELI_EXTERNAL_GYRO:
-			g.heli_ext_gyro_gain = tuning_value;
+			motors.ext_gyro_gain = tuning_value;
 			break;
 		#endif
 
diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde
index 7ab489e91ee7e70ced4552ea9d73410e68545010..f89960bbe500b0e370e907cace2a5ac5222f86bf 100644
--- a/ArduCopter/Attitude.pde
+++ b/ArduCopter/Attitude.pde
@@ -59,7 +59,7 @@ get_stabilize_pitch(int32_t target_angle)
 static int16_t
 get_stabilize_yaw(int32_t target_angle)
 {
-	static int8_t log_counter = 0;
+	static int8_t log_counter = 0;		// used to slow down logging of PID values to dataflash
 	int32_t target_rate,i_term;
 	int32_t angle_error;
 	int32_t output;
@@ -80,7 +80,7 @@ get_stabilize_yaw(int32_t target_angle)
 
 	// do not use rate controllers for helicotpers with external gyros
 #if FRAME_CONFIG == HELI_FRAME
-	if(!g.heli_ext_gyro_enabled){
+	if(!motors.ext_gyro_enabled){
 		output = get_rate_yaw(target_rate) + i_term;
 	}else{
 		output = constrain((target_rate + i_term), -4500, 4500);
@@ -95,7 +95,7 @@ get_stabilize_yaw(int32_t target_angle)
 		log_counter++;
 		if( log_counter >= 10 ) {	// (update rate / desired output rate) = (100hz / 10hz) = 10
 			log_counter = 0;
-			Log_Write_PID(CH6_YAW_KP, angle_error, target_rate, i_term, 0, output, g.pi_stabilize_yaw.kP());
+			Log_Write_PID(CH6_YAW_KP, angle_error, target_rate, i_term, 0, output, tuning_value);
 		}
 	}
 #endif
@@ -131,8 +131,11 @@ get_acro_yaw(int32_t target_rate)
 static int16_t
 get_rate_roll(int32_t target_rate)
 {
+	static int8_t log_counter = 0;					// used to slow down logging of PID values to dataflash
 	static int32_t last_rate = 0;					// previous iterations rate
+	int32_t p,i,d;									// used to capture pid values for logging
 	int32_t current_rate;							// this iteration's rate
+	int32_t rate_error;								// simply target_rate - current_rate
 	int32_t rate_d;  								// roll's acceleration
 	int32_t output;									// output from pid controller
 	int32_t rate_d_dampener;						// value to dampen output based on acceleration
@@ -147,22 +150,43 @@ get_rate_roll(int32_t target_rate)
 	last_rate 		= current_rate;
 
 	// call pid controller
-	output 			= g.pid_rate_roll.get_pid(target_rate - current_rate, G_Dt);
+	rate_error	= target_rate - current_rate;
+	p 			= g.pid_rate_roll.get_p(rate_error);
+	i			= g.pid_rate_roll.get_i(rate_error, G_Dt);
+	d			= g.pid_rate_roll.get_d(rate_error, G_Dt);
+	output		= p + i + d;
 
 	// Dampening output with D term
 	rate_d_dampener = rate_d * roll_scale_d;
 	rate_d_dampener = constrain(rate_d_dampener, -400, 400);
 	output -= rate_d_dampener;
 
+	// constrain output
+	output = constrain(output, -2500, 2500);
+
+#if LOGGING_ENABLED == ENABLED
+	// log output if PID logging is on and we are tuning the rate P, I or D gains
+	if( g.log_bitmask & MASK_LOG_PID && (g.radio_tuning == CH6_RATE_KP || g.radio_tuning == CH6_RATE_KI || g.radio_tuning == CH6_RATE_KD) ) {
+		log_counter++;
+		if( log_counter >= 10 ) {	// (update rate / desired output rate) = (100hz / 10hz) = 10
+			log_counter = 0;
+			Log_Write_PID(CH6_RATE_KP, rate_error, p, i, d-rate_d_dampener, output, tuning_value);
+		}
+	}
+#endif
+
 	// output control
-	return constrain(output, -2500, 2500);
+	return output;
 }
 
 static int16_t
 get_rate_pitch(int32_t target_rate)
 {
+	static int8_t log_counter = 0;					// used to slow down logging of PID values to dataflash
 	static int32_t last_rate = 0;					// previous iterations rate
+	int32_t p,i,d;									// used to capture pid values for logging
 	int32_t current_rate;							// this iteration's rate
+	int32_t rate_error;								// simply target_rate - current_rate
 	int32_t rate_d;  								// roll's acceleration
 	int32_t output;									// output from pid controller
 	int32_t rate_d_dampener;						// value to dampen output based on acceleration
@@ -177,22 +201,40 @@ get_rate_pitch(int32_t target_rate)
 	last_rate 		= current_rate;
 
 	// call pid controller
-	output 			= g.pid_rate_pitch.get_pid(target_rate - current_rate, G_Dt);
+	rate_error	= target_rate - current_rate;
+	p 			= g.pid_rate_pitch.get_p(rate_error);
+	i 			= g.pid_rate_pitch.get_i(rate_error, G_Dt);
+	d 			= g.pid_rate_pitch.get_d(rate_error, G_Dt);
+	output		= p + i + d;
 
 	// Dampening output with D term
 	rate_d_dampener = rate_d * pitch_scale_d;
 	rate_d_dampener = constrain(rate_d_dampener, -400, 400);
 	output -= rate_d_dampener;
 
+	// constrain output
+	output = constrain(output, -2500, 2500);
+
+#if LOGGING_ENABLED == ENABLED
+	// log output if PID logging is on and we are tuning the rate P, I or D gains
+	if( g.log_bitmask & MASK_LOG_PID && (g.radio_tuning == CH6_RATE_KP || g.radio_tuning == CH6_RATE_KI || g.radio_tuning == CH6_RATE_KD) ) {
+		log_counter++;
+		if( log_counter >= 10 ) {	// (update rate / desired output rate) = (100hz / 10hz) = 10
+			log_counter = 0;
+			Log_Write_PID(CH6_RATE_KP+100, rate_error, p, i, d-rate_d_dampener, output, tuning_value);
+		}
+	}
+#endif
+
 	// output control
-	return constrain(output, -2500, 2500);
+	return output;
 }
 
 static int16_t
 get_rate_yaw(int32_t target_rate)
 {
-	static int8_t log_counter = 0;
-	int32_t p,i,d;
+	static int8_t log_counter = 0;					// used to slow down logging of PID values to dataflash
+	int32_t p,i,d;									// used to capture pid values for logging
 	int32_t rate_error;
 	int32_t output;
 
@@ -218,7 +260,7 @@ get_rate_yaw(int32_t target_rate)
 		log_counter++;
 		if( log_counter >= 10 ) {	// (update rate / desired output rate) = (100hz / 10hz) = 10
 			log_counter = 0;
-			Log_Write_PID(CH6_YAW_RATE_KP, rate_error, p, i, d, output, g.pid_rate_yaw.kP());
+			Log_Write_PID(CH6_YAW_RATE_KP, rate_error, p, i, d, output, tuning_value);
 		}
 	}
 #endif
@@ -390,6 +432,20 @@ static int16_t get_angle_boost(int16_t value)
 //	return (int)(temp * value);
 }
 
+#if FRAME_CONFIG == HELI_FRAME
+// heli_angle_boost - adds a boost depending on roll/pitch values
+// equivalent of quad's angle_boost function
+// throttle value should be 0 ~ 1000
+static int16_t heli_get_angle_boost(int16_t throttle)
+{
+    float angle_boost_factor = cos_pitch_x * cos_roll_x;
+	angle_boost_factor = 1.0 - constrain(angle_boost_factor, .5, 1.0);
+	int throttle_above_mid = max(throttle - motors.throttle_mid,0);
+	return throttle + throttle_above_mid*angle_boost_factor;
+
+}
+#endif // HELI_FRAME
+
 #define NUM_G_SAMPLES 40
 
 #if ACCEL_ALT_HOLD == 2
diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde
index 445716b5170d0b7bd8d158bfb102a037f9d66c6a..f6692591d9eb966361b2cee9d47a5e93527357f9 100644
--- a/ArduCopter/GCS_Mavlink.pde
+++ b/ArduCopter/GCS_Mavlink.pde
@@ -74,7 +74,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
 
     uint8_t status 		= MAV_STATE_ACTIVE;
 
-    if (!motor_armed) {
+    if (!motors.armed()) {
         status 		= MAV_STATE_STANDBY;
     }
 
@@ -197,7 +197,7 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
     #else
 		#if X_PLANE == ENABLED
 			 /* update by JLN for X-Plane HIL */
-			if(motor_armed  == true && motor_auto_armed == true){
+			if(motors.armed() && motors.auto_armed()){
 				mavlink_msg_rc_channels_scaled_send(
 					chan,
 					g.rc_1.servo_out,
@@ -259,14 +259,14 @@ static void NOINLINE send_radio_out(mavlink_channel_t chan)
 {
     mavlink_msg_servo_output_raw_send(
         chan,
-        motor_out[0],
-        motor_out[1],
-        motor_out[2],
-        motor_out[3],
-        motor_out[4],
-        motor_out[5],
-        motor_out[6],
-        motor_out[7]);
+        motors.motor_out[AP_MOTORS_MOT_1],
+        motors.motor_out[AP_MOTORS_MOT_2],
+        motors.motor_out[AP_MOTORS_MOT_3],
+        motors.motor_out[AP_MOTORS_MOT_4],
+        motors.motor_out[AP_MOTORS_MOT_5],
+        motors.motor_out[AP_MOTORS_MOT_6],
+        motors.motor_out[AP_MOTORS_MOT_7],
+        motors.motor_out[AP_MOTORS_MOT_8]);
 }
 
 static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
diff --git a/ArduCopter/Log.pde b/ArduCopter/Log.pde
index a4a3e4a157d4d74cc09f3bac4b51ae980d1ee333..0a0b350168208296ff15c99f22f4d372fe435540 100644
--- a/ArduCopter/Log.pde
+++ b/ArduCopter/Log.pde
@@ -357,52 +357,52 @@ static void Log_Write_Motors()
 	DataFlash.WriteByte(LOG_MOTORS_MSG);
 
 	#if FRAME_CONFIG ==	TRI_FRAME
-	DataFlash.WriteInt(motor_out[CH_1]);//1
-	DataFlash.WriteInt(motor_out[CH_2]);//2
-	DataFlash.WriteInt(motor_out[CH_4]);//3
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//1
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//2
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//3
 	DataFlash.WriteInt(g.rc_4.radio_out);//4
 
 	#elif FRAME_CONFIG == HEXA_FRAME
-	DataFlash.WriteInt(motor_out[CH_1]);//1
-	DataFlash.WriteInt(motor_out[CH_2]);//2
-	DataFlash.WriteInt(motor_out[CH_3]);//3
-	DataFlash.WriteInt(motor_out[CH_4]);//4
-	DataFlash.WriteInt(motor_out[CH_7]);//5
-	DataFlash.WriteInt(motor_out[CH_8]);//6
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//1
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//2
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]);//3
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//4
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_5]);//5
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_6]);//6
 
 	#elif FRAME_CONFIG == Y6_FRAME
 	//left
-	DataFlash.WriteInt(motor_out[CH_2]);//1
-	DataFlash.WriteInt(motor_out[CH_3]);//2
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//1
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]);//2
 	//right
-	DataFlash.WriteInt(motor_out[CH_7]);//3
-	DataFlash.WriteInt(motor_out[CH_1]);//4
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_5]);//3
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//4
 	//back
-	DataFlash.WriteInt(motor_out[CH_8]);//5
-	DataFlash.WriteInt(motor_out[CH_4]);//6
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_6]);//5
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//6
 
 	#elif FRAME_CONFIG == OCTA_FRAME || FRAME_CONFIG == OCTA_QUAD_FRAME
-	DataFlash.WriteInt(motor_out[CH_1]);//1
-	DataFlash.WriteInt(motor_out[CH_2]);//2
-	DataFlash.WriteInt(motor_out[CH_3]);//3
-	DataFlash.WriteInt(motor_out[CH_4]);//4
-	DataFlash.WriteInt(motor_out[CH_7]);//5
-	DataFlash.WriteInt(motor_out[CH_8]); //6
-	DataFlash.WriteInt(motor_out[CH_10]);//7
-	DataFlash.WriteInt(motor_out[CH_11]);//8
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//1
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//2
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]);//3
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//4
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_5]);//5
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_6]); //6
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_7]);//7
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_8]);//8
 
 	#elif FRAME_CONFIG == HELI_FRAME
-	DataFlash.WriteInt(heli_servo_out[0]);//1
-	DataFlash.WriteInt(heli_servo_out[1]);//2
-	DataFlash.WriteInt(heli_servo_out[2]);//3
-	DataFlash.WriteInt(heli_servo_out[3]);//4
-	DataFlash.WriteInt(g.heli_ext_gyro_gain);//5
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//1
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//2
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]);//3
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//4
+	DataFlash.WriteInt(motors.ext_gyro_gain);//5
 
 	#else // quads
-	DataFlash.WriteInt(motor_out[CH_1]);//1
-	DataFlash.WriteInt(motor_out[CH_2]);//2
-	DataFlash.WriteInt(motor_out[CH_3]);//3
-	DataFlash.WriteInt(motor_out[CH_4]);//4
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//1
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//2
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]);//3
+	DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//4
 	#endif
 
 	DataFlash.WriteByte(END_BYTE);
diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h
index beb92f70b0c2b58e9823f7525ade63482cac7c83..2492f8e3c0351b15fd85a0f7533a1acbc4e4b132 100644
--- a/ArduCopter/Parameters.h
+++ b/ArduCopter/Parameters.h
@@ -17,7 +17,7 @@ public:
 	// The increment will prevent old parameters from being used incorrectly
 	// by newer code.
 	//
-	static const uint16_t k_format_version = 117;
+	static const uint16_t k_format_version = 118;
 
 	// The parameter software_type is set up solely for ground station use
 	// and identifies the software type (eg ArduPilotMega versus ArduCopterMega)
@@ -65,23 +65,13 @@ public:
 	k_param_heli_servo_2,
 	k_param_heli_servo_3,
 	k_param_heli_servo_4,
-	k_param_heli_servo1_pos ,
-	k_param_heli_servo2_pos,
-	k_param_heli_servo3_pos,
-	k_param_heli_roll_max,
-	k_param_heli_pitch_max,
-	k_param_heli_collective_min,
-	k_param_heli_collective_max,
-	k_param_heli_collective_mid,
-	k_param_heli_ext_gyro_enabled,
-	k_param_heli_ext_gyro_gain,
-	k_param_heli_servo_averaging,
-	k_param_heli_servo_manual,
-	k_param_heli_phase_angle,
-	k_param_heli_collective_yaw_effect,
-	k_param_heli_h1_swash_enabled, //98
 	#endif
 
+	//
+	// 90: Motors
+	//
+	k_param_motors = 90,
+
 	// 110: Telemetry control
 	//
 	k_param_gcs0 = 110,
@@ -103,15 +93,14 @@ public:
 	k_param_compass,
 	k_param_sonar_enabled,
 	k_param_frame_orientation,
-	k_param_top_bottom_ratio,
 	k_param_optflow_enabled,
 	k_param_low_voltage,
 	k_param_ch7_option,
 	k_param_auto_slew_rate,
 	k_param_sonar_type,
-	k_param_super_simple, //155
+	k_param_super_simple,
 	k_param_rtl_land_enabled,
-	k_param_axis_enabled,
+	k_param_axis_enabled, //157
 
 	//
 	// 160: Navigation parameters
@@ -266,23 +255,12 @@ public:
 	AP_Int16	radio_tuning_high;
 	AP_Int16	radio_tuning_low;
 	AP_Int8		frame_orientation;
-	AP_Float	top_bottom_ratio;
 	AP_Int8		ch7_option;
 	AP_Int16	auto_slew_rate;
 
 	#if FRAME_CONFIG ==	HELI_FRAME
 	// Heli
 	RC_Channel	heli_servo_1, heli_servo_2, heli_servo_3, heli_servo_4;	// servos for swash plate and tail
-	AP_Int16	heli_servo1_pos, heli_servo2_pos, heli_servo3_pos;		// servo positions (3 because we don't need pos for tail servo)
-	AP_Int16	heli_roll_max, heli_pitch_max;	// maximum allowed roll and pitch of swashplate
-	AP_Int16	heli_collective_min, heli_collective_max, heli_collective_mid;		// min and max collective.	mid = main blades at zero pitch
-	AP_Int8		heli_ext_gyro_enabled;	// 0 = no external tail gyro, 1 = external tail gyro
-	AP_Int16	heli_ext_gyro_gain;		// radio output 1000~2000 (value output on CH_7)
-	AP_Int8		heli_servo_averaging;	// 0 or 1 = no averaging (250hz) for **digital servos**, 2=average of two samples (125hz), 3=three samples (83.3hz) **analog servos**, 4=four samples (62.5hz), 5=5 samples(50hz)
-	AP_Int8		heli_servo_manual;	    // 0 = normal mode, 1 = radio inputs directly control swash.  required for swash set-up
-	AP_Int16	heli_phase_angle;		// 0 to 360 degrees.  specifies mixing between roll and pitch for helis
-	AP_Float	heli_collective_yaw_effect;	// -5.0 ~ 5.0.  Feed forward control from collective to yaw.  1.0 = move rudder right 1% for every 1% of collective above the mid point
-	AP_Int8		heli_h1_swash_enabled; 	// 0 = CCPM swashplate, 1 = H1 swashplate (no servo mixing)
 	#endif
 
 	// RC channels
@@ -384,28 +362,9 @@ public:
 	radio_tuning_high 		(1000),
 	radio_tuning_low 		(0),
 	frame_orientation 		(FRAME_ORIENTATION),
-	top_bottom_ratio 		(TOP_BOTTOM_RATIO),
 	ch7_option 				(CH7_OPTION),
 	auto_slew_rate			(AUTO_SLEW_RATE),
 
-	#if FRAME_CONFIG ==	HELI_FRAME
-	heli_servo1_pos				(-60),
-	heli_servo2_pos				(60),
-	heli_servo3_pos				(180),
-	heli_roll_max				(4500),
-	heli_pitch_max				(4500),
-	heli_collective_min			(1250),
-	heli_collective_max			(1750),
-	heli_collective_mid			(1500),
-	heli_ext_gyro_enabled		(0),
-	heli_ext_gyro_gain			(1350),
-	heli_servo_averaging		(0),
-	heli_servo_manual			(0),
-	heli_phase_angle			(0),
-	heli_collective_yaw_effect	(0),
-	heli_h1_swash_enabled		(0),
-	#endif
-
     rc_speed(RC_FAST_SPEED),
 
 	camera_pitch_gain 		(CAM_PITCH_GAIN),
@@ -433,13 +392,14 @@ public:
 
 	// PI controller	initial P			initial I			initial imax
 	//----------------------------------------------------------------------
+	pi_loiter_lat		(LOITER_P,			LOITER_I,			LOITER_IMAX * 100),
+	pi_loiter_lon		(LOITER_P,			LOITER_I,			LOITER_IMAX * 100),
+
 	pi_stabilize_roll	(STABILIZE_ROLL_P,	STABILIZE_ROLL_I,	STABILIZE_ROLL_IMAX * 100),
 	pi_stabilize_pitch	(STABILIZE_PITCH_P,	STABILIZE_PITCH_I,	STABILIZE_PITCH_IMAX * 100),
 	pi_stabilize_yaw	(STABILIZE_YAW_P,	STABILIZE_YAW_I,	STABILIZE_YAW_IMAX * 100),
 
-	pi_alt_hold			(ALT_HOLD_P,		ALT_HOLD_I,			ALT_HOLD_IMAX),
-	pi_loiter_lat		(LOITER_P,			LOITER_I,			LOITER_IMAX * 100),
-	pi_loiter_lon		(LOITER_P,			LOITER_I,			LOITER_IMAX * 100)
+	pi_alt_hold			(ALT_HOLD_P,		ALT_HOLD_I,			ALT_HOLD_IMAX)
 	{
 	}
 };
diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde
index 4855031e41632447ec464e4043b670e0d1c928ad..8a84e81ac46f8e431e8ee94852ef83e39a2b2a40 100644
--- a/ArduCopter/Parameters.pde
+++ b/ArduCopter/Parameters.pde
@@ -67,7 +67,6 @@ static const AP_Param::Info var_info[] PROGMEM = {
 	GSCALAR(radio_tuning_low, "TUNE_LOW"),
 	GSCALAR(radio_tuning_high, "TUNE_HIGH"),
 	GSCALAR(frame_orientation, "FRAME"),
-	GSCALAR(top_bottom_ratio, "TB_RATIO"),
 	GSCALAR(ch7_option, "CH7_OPT"),
 	GSCALAR(auto_slew_rate, "AUTO_SLEW"),
 
@@ -76,21 +75,6 @@ static const AP_Param::Info var_info[] PROGMEM = {
 	GGROUP(heli_servo_2,	"HS2_", RC_Channel),
 	GGROUP(heli_servo_3,	"HS3_", RC_Channel),
 	GGROUP(heli_servo_4,	"HS4_", RC_Channel),
-	GSCALAR(heli_servo1_pos,	"SV1_POS"),
-	GSCALAR(heli_servo2_pos,	"SV2_POS"),
-	GSCALAR(heli_servo3_pos,	"SV3_POS"),
-	GSCALAR(heli_roll_max,	"ROL_MAX"),
-	GSCALAR(heli_pitch_max,	"PIT_MAX"),
-	GSCALAR(heli_collective_min,	"COL_MIN"),
-	GSCALAR(heli_collective_max,	"COL_MAX"),
-	GSCALAR(heli_collective_mid,	"COL_MID"),
-	GSCALAR(heli_ext_gyro_enabled,	"GYR_ENABLE"),
-	GSCALAR(heli_h1_swash_enabled,	"H1_ENABLE"),
-	GSCALAR(heli_ext_gyro_gain,	"GYR_GAIN"),
-	GSCALAR(heli_servo_averaging,	"SV_AVG"),
-	GSCALAR(heli_servo_manual,	"HSV_MAN"),
-	GSCALAR(heli_phase_angle,	"H_PHANG"),
-	GSCALAR(heli_collective_yaw_effect,	"H_COLYAW"),
 	#endif
 
 	// RC channel
@@ -151,6 +135,12 @@ static const AP_Param::Info var_info[] PROGMEM = {
 	GOBJECT(gcs0,			"SR0_",     GCS_MAVLINK),
 	GOBJECT(gcs3,			"SR3_",     GCS_MAVLINK),
 	GOBJECT(imu,			"IMU_",     IMU)
+
+	#if FRAME_CONFIG ==	HELI_FRAME
+	,GOBJECT(motors,	"H_",		AP_MotorsHeli)
+	#else
+	,GOBJECT(motors,	"MOT_",		AP_Motors)
+	#endif
 };
 
 
diff --git a/ArduCopter/config_channels.h b/ArduCopter/config_channels.h
index 7fe44b0677b6c51e69e27d45ee330b620573531c..40fa0eb8339388f1c1fa56c1e00918cdf17e237a 100644
--- a/ArduCopter/config_channels.h
+++ b/ArduCopter/config_channels.h
@@ -19,44 +19,6 @@
 #include "config.h"     // Parent Config File
 #include "APM_Config.h" // User Overrides
 
-//
-//
-// Output CH mapping for ArduCopter motor channels
-//
-//
-#if CONFIG_CHANNELS == CHANNEL_CONFIG_DEFAULT
-# if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
-#  define MOT_1 CH_1
-#  define MOT_2 CH_2
-#  define MOT_3 CH_3
-#  define MOT_4 CH_4
-#  define MOT_5 CH_5
-#  define MOT_6 CH_6
-#  define MOT_7 CH_7
-#  define MOT_8 CH_8
-# elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
-#  define MOT_1 CH_1
-#  define MOT_2 CH_2
-#  define MOT_3 CH_3
-#  define MOT_4 CH_4
-#  define MOT_5 CH_7
-#  define MOT_6 CH_8
-#  define MOT_7 CH_10
-#  define MOT_8 CH_11
-# endif 
-#endif
-
-//
-//
-// Output CH mapping for TRI_FRAME yaw servo
-//
-//
-#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
-# define CH_TRI_YAW   CH_7
-#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
-# define CH_TRI_YAW   CH_7
-#endif
-
 //
 //
 // Output CH mapping for Aux channels
diff --git a/ArduCopter/heli.pde b/ArduCopter/heli.pde
deleted file mode 100644
index 7940adee988fe778021aff824c5cc18b633653b3..0000000000000000000000000000000000000000
--- a/ArduCopter/heli.pde
+++ /dev/null
@@ -1,334 +0,0 @@
-/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
-
-#if FRAME_CONFIG ==	HELI_FRAME
-
-#define HELI_SERVO_AVERAGING_DIGITAL 0  // 250Hz
-#define HELI_SERVO_AVERAGING_ANALOG  2  // 125Hz
-
-static bool heli_swash_initialised = false;
-static int heli_throttle_mid = 0;  // throttle mid point in pwm form (i.e. 0 ~ 1000)
-static float heli_collective_scalar = 1;  // throttle scalar to convert pwm form (i.e. 0 ~ 1000) passed in to actual servo range (i.e 1250~1750 would be 500)
-
-// heli_servo_averaging:
-//   0 or 1 = no averaging, 250hz
-//   2 = average two samples, 125hz
-//   3 = averaging three samples = 83.3 hz
-//   4 = averaging four samples = 62.5 hz
-//   5 = averaging 5 samples = 50hz
-//   digital = 0 / 250hz, analog = 2 / 83.3
-
-// reset swash for maximum movements - used for set-up
-static void heli_reset_swash()
-{
-	// free up servo ranges
-	g.heli_servo_1.radio_min = 1000;
-	g.heli_servo_1.radio_max = 2000;
-	g.heli_servo_2.radio_min = 1000;
-	g.heli_servo_2.radio_max = 2000;
-	g.heli_servo_3.radio_min = 1000;
-	g.heli_servo_3.radio_max = 2000;
-
-	if (!g.heli_h1_swash_enabled){			//CCPM Swashplate, perform servo control mixing
-		
-		// roll factors
-		heli_rollFactor[CH_1] = cos(radians(g.heli_servo1_pos + 90 - g.heli_phase_angle));
-		heli_rollFactor[CH_2] = cos(radians(g.heli_servo2_pos + 90 - g.heli_phase_angle));
-		heli_rollFactor[CH_3] = cos(radians(g.heli_servo3_pos + 90 - g.heli_phase_angle));
-				
-		// pitch factors
-		heli_pitchFactor[CH_1] = cos(radians(g.heli_servo1_pos - g.heli_phase_angle));
-		heli_pitchFactor[CH_2] = cos(radians(g.heli_servo2_pos - g.heli_phase_angle));
-		heli_pitchFactor[CH_3] = cos(radians(g.heli_servo3_pos - g.heli_phase_angle));
-		
-		// collective factors
-		heli_collectiveFactor[CH_1] = 1;
-		heli_collectiveFactor[CH_2] = 1;
-		heli_collectiveFactor[CH_3] = 1;
-		
-	}else{  								//H1 Swashplate, keep servo outputs seperated
-
-		// roll factors
-		heli_rollFactor[CH_1] = 1;
-		heli_rollFactor[CH_2] = 0;
-		heli_rollFactor[CH_3] = 0;
-	
-		// pitch factors
-		heli_pitchFactor[CH_1] = 0;
-		heli_pitchFactor[CH_2] = 1;
-		heli_pitchFactor[CH_3] = 0;
-		
-		// collective factors
-		heli_collectiveFactor[CH_1] = 0;
-		heli_collectiveFactor[CH_2] = 0;
-		heli_collectiveFactor[CH_3] = 1;
-	}
-
-	// set throttle scaling
-	heli_collective_scalar = ((float)(g.rc_3.radio_max - g.rc_3.radio_min))/1000.0;
-
-	// we must be in set-up mode so mark swash as uninitialised
-	heli_swash_initialised = false;
-}
-
-// initialise the swash
-static void heli_init_swash()
-{
-    int i;
-
-	// swash servo initialisation
-	g.heli_servo_1.set_range(0,1000);
-	g.heli_servo_2.set_range(0,1000);
-	g.heli_servo_3.set_range(0,1000);
-	g.heli_servo_4.set_angle(4500);
-
-	// ensure g.heli_coll values are reasonable
-	if( g.heli_collective_min >= g.heli_collective_max ) {
-	    g.heli_collective_min = 1000;
-		g.heli_collective_max = 2000;
-	}
-	g.heli_collective_mid = constrain(g.heli_collective_mid, g.heli_collective_min, g.heli_collective_max);
-
-	// calculate throttle mid point
-	heli_throttle_mid = ((float)(g.heli_collective_mid-g.heli_collective_min))/((float)(g.heli_collective_max-g.heli_collective_min))*1000.0;
-
-	// determine scalar throttle input
-	heli_collective_scalar = ((float)(g.heli_collective_max-g.heli_collective_min))/1000.0;
-
-	if (!g.heli_h1_swash_enabled){			//CCPM Swashplate, perform control mixing
-		
-		// roll factors
-		heli_rollFactor[CH_1] = cos(radians(g.heli_servo1_pos + 90 - g.heli_phase_angle));
-		heli_rollFactor[CH_2] = cos(radians(g.heli_servo2_pos + 90 - g.heli_phase_angle));
-		heli_rollFactor[CH_3] = cos(radians(g.heli_servo3_pos + 90 - g.heli_phase_angle));
-				
-		// pitch factors
-		heli_pitchFactor[CH_1] = cos(radians(g.heli_servo1_pos - g.heli_phase_angle));
-		heli_pitchFactor[CH_2] = cos(radians(g.heli_servo2_pos - g.heli_phase_angle));
-		heli_pitchFactor[CH_3] = cos(radians(g.heli_servo3_pos - g.heli_phase_angle));
-		
-		// collective factors
-		heli_collectiveFactor[CH_1] = 1;
-		heli_collectiveFactor[CH_2] = 1;
-		heli_collectiveFactor[CH_3] = 1;
-		
-	}else{  								//H1 Swashplate, keep servo outputs seperated
-
-		// roll factors
-		heli_rollFactor[CH_1] = 1;
-		heli_rollFactor[CH_2] = 0;
-		heli_rollFactor[CH_3] = 0;
-	
-		// pitch factors
-		heli_pitchFactor[CH_1] = 0;
-		heli_pitchFactor[CH_2] = 1;
-		heli_pitchFactor[CH_3] = 0;
-		
-		// collective factors
-		heli_collectiveFactor[CH_1] = 0;
-		heli_collectiveFactor[CH_2] = 0;
-		heli_collectiveFactor[CH_3] = 1;
-	}
-
-	// servo min/max values
-	g.heli_servo_1.radio_min = 1000;
-	g.heli_servo_1.radio_max = 2000;
-	g.heli_servo_2.radio_min = 1000;
-	g.heli_servo_2.radio_max = 2000;
-	g.heli_servo_3.radio_min = 1000;
-	g.heli_servo_3.radio_max = 2000;
-
-	// reset the servo averaging
-	for( i=0; i<=3; i++ )
-	    heli_servo_out[i] = 0;
-
-    // double check heli_servo_averaging is reasonable
-	if( g.heli_servo_averaging < 0 || g.heli_servo_averaging > 5 ) {
-	    g.heli_servo_averaging = 0;
-		g.heli_servo_averaging.save();
-	}
-
-	// mark swash as initialised
-	heli_swash_initialised = true;
-}
-
-static void heli_move_servos_to_mid()
-{
-    // call multiple times to force through the servo averaging
-    for( int i=0; i<5; i++ ) {
-		heli_move_swash(0,0,500,0);
-		delay(20);
-	}
-}
-
-//
-// heli_move_swash - moves swash plate to attitude of parameters passed in
-//                 - expected ranges:
-//                       roll : -4500 ~ 4500
-//                       pitch: -4500 ~ 4500
-//                       collective: 0 ~ 1000
-//                       yaw:   -4500 ~ 4500
-//
-static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_out)
-{
-	int yaw_offset = 0;
-	int coll_out_scaled;
-
-	if( g.heli_servo_manual == 1 ) {  // are we in manual servo mode? (i.e. swash set-up mode)?
-		// check if we need to freeup the swash
-		if( heli_swash_initialised ) {
-			heli_reset_swash();
-		}
-		coll_out_scaled = coll_out * heli_collective_scalar + g.rc_3.radio_min - 1000;
-	}else{  // regular flight mode
-
-		// check if we need to reinitialise the swash
-		if( !heli_swash_initialised ) {
-			heli_init_swash();
-		}
-
-	    // ensure values are acceptable:
-		roll_out = constrain(roll_out, (int)-g.heli_roll_max, (int)g.heli_roll_max);
-		pitch_out = constrain(pitch_out, (int)-g.heli_pitch_max, (int)g.heli_pitch_max);
-		coll_out = constrain(coll_out, 0, 1000);
-		coll_out_scaled = coll_out * heli_collective_scalar + g.heli_collective_min - 1000;
-		
-		// rescale roll_out and pitch-out into the min and max ranges to provide linear motion 
-		// across the input range instead of stopping when the input hits the constrain value
-		// these calculations are based on an assumption of the user specified roll_max and pitch_max 
-		// coming into this equation at 4500 or less, and based on the original assumption of the  
-		// total g.heli_servo_x.servo_out range being -4500 to 4500.
-		roll_out = (-g.heli_roll_max + (float)( 2 * g.heli_roll_max * (roll_out + 4500.0)/9000.0));
-		pitch_out = (-g.heli_pitch_max + (float)(2 * g.heli_pitch_max * (pitch_out + 4500.0)/9000.0));
-		
-
-		// rudder feed forward based on collective
-		#if HIL_MODE == HIL_MODE_DISABLED  // don't do rudder feed forward in simulator
-		if( !g.heli_ext_gyro_enabled ) {
-			yaw_offset = g.heli_collective_yaw_effect * abs(coll_out_scaled - heli_throttle_mid);
-		}
-		#endif
-	}
-
-	// swashplate servos
-	g.heli_servo_1.servo_out = (heli_rollFactor[CH_1] * roll_out + heli_pitchFactor[CH_1] * pitch_out)/10 + heli_collectiveFactor[CH_1] * coll_out_scaled + (g.heli_servo_1.radio_trim-1500) + g.heli_h1_swash_enabled * 500;
-	g.heli_servo_2.servo_out = (heli_rollFactor[CH_2] * roll_out + heli_pitchFactor[CH_2] * pitch_out)/10 + heli_collectiveFactor[CH_2] * coll_out_scaled + (g.heli_servo_2.radio_trim-1500) + g.heli_h1_swash_enabled * 500;
-	g.heli_servo_3.servo_out = (heli_rollFactor[CH_3] * roll_out + heli_pitchFactor[CH_3] * pitch_out)/10 + heli_collectiveFactor[CH_3] * coll_out_scaled + (g.heli_servo_3.radio_trim-1500);
-	g.heli_servo_4.servo_out = yaw_out + yaw_offset;
-
-	// use servo_out to calculate pwm_out and radio_out
-	g.heli_servo_1.calc_pwm();
-	g.heli_servo_2.calc_pwm();
-	g.heli_servo_3.calc_pwm();
-	g.heli_servo_4.calc_pwm();
-
-	// add the servo values to the averaging
-	heli_servo_out[0] += g.heli_servo_1.radio_out;
-	heli_servo_out[1] += g.heli_servo_2.radio_out;
-	heli_servo_out[2] += g.heli_servo_3.radio_out;
-	heli_servo_out[3] += g.heli_servo_4.radio_out;
-	heli_servo_out_count++;
-
-	// is it time to move the servos?
-	if( heli_servo_out_count >= g.heli_servo_averaging ) {
-
-	    // average the values if necessary
-	    if( g.heli_servo_averaging >= 2 ) {
-		    heli_servo_out[0] /= g.heli_servo_averaging;
-			heli_servo_out[1] /= g.heli_servo_averaging;
-			heli_servo_out[2] /= g.heli_servo_averaging;
-			heli_servo_out[3] /= g.heli_servo_averaging;
-		}
-
-		// actually move the servos
-		APM_RC.OutputCh(CH_1, heli_servo_out[0]);
-		APM_RC.OutputCh(CH_2, heli_servo_out[1]);
-		APM_RC.OutputCh(CH_3, heli_servo_out[2]);
-		APM_RC.OutputCh(CH_4, heli_servo_out[3]);
-
-		// output gyro value
-		if( g.heli_ext_gyro_enabled ) {
-			APM_RC.OutputCh(CH_7, g.heli_ext_gyro_gain);
-		}
-
-		#if INSTANT_PWM == 1
-		// InstantPWM
-		APM_RC.Force_Out0_Out1();
-		APM_RC.Force_Out2_Out3();
-		#endif
-
-		// reset the averaging
-		heli_servo_out_count = 0;
-		heli_servo_out[0] = 0;
-		heli_servo_out[1] = 0;
-		heli_servo_out[2] = 0;
-		heli_servo_out[3] = 0;
-	}
-}
-
-static void init_motors_out()
-{
-	#if INSTANT_PWM == 0
-    APM_RC.SetFastOutputChannels( _BV(CH_1) | _BV(CH_2) | _BV(CH_3) | _BV(CH_4), g.rc_speed );
-	#endif
-}
-
-static void motors_output_enable()
-{
-  APM_RC.enable_out(CH_1);
-  APM_RC.enable_out(CH_2);
-  APM_RC.enable_out(CH_3);
-  APM_RC.enable_out(CH_4);
-  APM_RC.enable_out(CH_5);
-  APM_RC.enable_out(CH_6);
-  APM_RC.enable_out(CH_7);
-  APM_RC.enable_out(CH_8);
-}
-
-// these are not really motors, they're servos but we don't rename the function because it fits with the rest of the code better
-static void output_motors_armed()
-{
-    // if manual override (i.e. when setting up swash), pass pilot commands straight through to swash
-    if( g.heli_servo_manual == 1 ) {
-		g.rc_1.servo_out = g.rc_1.control_in;
-		g.rc_2.servo_out = g.rc_2.control_in;
-		g.rc_3.servo_out = g.rc_3.control_in;
-		g.rc_4.servo_out = g.rc_4.control_in;
-	}
-
-    //static int counter = 0;
-	g.rc_1.calc_pwm();
-	g.rc_2.calc_pwm();
-	g.rc_3.calc_pwm();
-	g.rc_4.calc_pwm();
-
-	heli_move_swash( g.rc_1.servo_out, g.rc_2.servo_out, g.rc_3.servo_out, g.rc_4.servo_out );
-}
-
-// for helis - armed or disarmed we allow servos to move
-static void output_motors_disarmed()
-{
-	if(g.rc_3.control_in > 0){
-		// we have pushed up the throttle, remove safety
-		motor_auto_armed = true;
-	}
-
-	output_motors_armed();
-}
-
-static void output_motor_test()
-{
-}
-
-// heli_angle_boost - adds a boost depending on roll/pitch values
-// equivalent of quad's angle_boost function
-// throttle value should be 0 ~ 1000
-static int16_t heli_get_angle_boost(int throttle)
-{
-    float angle_boost_factor = cos_pitch_x * cos_roll_x;
-	angle_boost_factor = 1.0 - constrain(angle_boost_factor, .5, 1.0);
-	int throttle_above_mid = max(throttle - heli_throttle_mid,0);
-	return throttle + throttle_above_mid*angle_boost_factor;
-
-}
-
-#endif // HELI_FRAME
diff --git a/ArduCopter/leds.pde b/ArduCopter/leds.pde
index 97b05f746e8fafeb91cf4939858ac8d80e850819..263c954ee816644e3718c87ad406f11859d0c96c 100644
--- a/ArduCopter/leds.pde
+++ b/ArduCopter/leds.pde
@@ -46,7 +46,7 @@ static void update_GPS_light(void)
 
 static void update_motor_light(void)
 {
-	if(motor_armed == false){
+	if(motors.armed() == false){
 		motor_light = !motor_light;
 
 		// blink
@@ -100,7 +100,7 @@ static void clear_leds()
 #if MOTOR_LEDS == 1
 static void update_motor_leds(void)
 {
-	if (motor_armed == true){
+	if (motors.armed()){
 		if (low_batt == true){
 	    	// blink rear
 			static bool blink = false;
diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde
index 0671fd2090c36924852108988c32ed4db5e50b1d..479e294da0b68f16837e96b7161465d156ff4171 100644
--- a/ArduCopter/motors.pde
+++ b/ArduCopter/motors.pde
@@ -26,7 +26,7 @@ static void arm_motors()
 			arming_counter = 0;
 
 		}else if (arming_counter == ARM_DELAY){
-			if(motor_armed == false){
+			if(motors.armed() == false){
 				// arm the motors and configure for flight
 				init_arm_motors();
 			}
@@ -46,7 +46,7 @@ static void arm_motors()
 			arming_counter = 0;
 
 		}else if (arming_counter == DISARM_DELAY){
-			if(motor_armed == true){
+			if(motors.armed()){
 				// arm the motors and configure for flight
 				init_disarm_motors();
 			}
@@ -82,8 +82,7 @@ static void init_arm_motors()
     if (gcs3.initialised) {
         Serial3.set_blocking_writes(false);
     }
-
-	motor_armed 	= true;
+	motors.armed(true);
 
 	#if PIEZO_ARMING == 1
 	piezo_beep();
@@ -130,7 +129,7 @@ static void init_disarm_motors()
 	gcs_send_text_P(SEVERITY_HIGH, PSTR("DISARMING MOTORS"));
 	#endif
 
-	motor_armed 	= false;
+	motors.armed(false);
 	compass.save_offsets();
 
 	g.throttle_cruise.save();
@@ -149,25 +148,6 @@ static void init_disarm_motors()
 static void
 set_servos_4()
 {
-	if (motor_armed == true && motor_auto_armed == true) {
-		// creates the radio_out and pwm_out values
-		output_motors_armed();
-	} else{
-		output_motors_disarmed();
-	}
-}
-
-int ch_of_mot( int mot ) {
-  switch (mot) {
-    case 1: return MOT_1;
-    case 2: return MOT_2;
-    case 3: return MOT_3;
-    case 4: return MOT_4;
-    case 5: return MOT_5;
-    case 6: return MOT_6;
-    case 7: return MOT_7;
-    case 8: return MOT_8;
-  }
-  return (-1);
+	motors.output();
 }
 
diff --git a/ArduCopter/motors_hexa.pde b/ArduCopter/motors_hexa.pde
deleted file mode 100644
index 10eae0b73b4a246bef3a38b778bbd334b23c85cb..0000000000000000000000000000000000000000
--- a/ArduCopter/motors_hexa.pde
+++ /dev/null
@@ -1,241 +0,0 @@
-/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
-
-#if FRAME_CONFIG ==	HEXA_FRAME
-
-static void init_motors_out()
-{
-	#if INSTANT_PWM == 0
-		APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4)
-                                     | _BV(MOT_5) | _BV(MOT_6), g.rc_speed);
-	#endif
-}
-
-static void motors_output_enable()
-{
-	APM_RC.enable_out(MOT_1);
-	APM_RC.enable_out(MOT_2);
-	APM_RC.enable_out(MOT_3);
-	APM_RC.enable_out(MOT_4);
-	APM_RC.enable_out(MOT_5);
-	APM_RC.enable_out(MOT_6);
-}
-
-static void output_motors_armed()
-{
-	int roll_out, pitch_out;
-	int out_min = g.rc_3.radio_min;
-	int out_max = g.rc_3.radio_max;
-
-	// Throttle is 0 to 1000 only
-	g.rc_3.servo_out 	= constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE);
-
-	if(g.rc_3.servo_out > 0)
-		out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
-
-	g.rc_1.calc_pwm();
-	g.rc_2.calc_pwm();
-	g.rc_3.calc_pwm();
-	g.rc_4.calc_pwm();
-
-	if(g.frame_orientation == X_FRAME){
-		roll_out 	 	= g.rc_1.pwm_out / 2;
-		pitch_out 	 	= (float)g.rc_2.pwm_out * .866;
-
-		//left side
-		motor_out[MOT_2]		= g.rc_3.radio_out + g.rc_1.pwm_out;		// CCW Middle
-		motor_out[MOT_3]		= g.rc_3.radio_out + roll_out + pitch_out;	// CW Front
-		motor_out[MOT_6]		 = g.rc_3.radio_out + roll_out - pitch_out;	// CW Back
-
-		//right side
-		motor_out[MOT_1]		= g.rc_3.radio_out - g.rc_1.pwm_out;		// CW Middle
-		motor_out[MOT_5] 	= g.rc_3.radio_out - roll_out + pitch_out;	// CCW Front
-		motor_out[MOT_4] 	= g.rc_3.radio_out - roll_out - pitch_out;	// CCW Back
-
-	}else{
-		roll_out 	 	= (float)g.rc_1.pwm_out * .866;
-		pitch_out 	 	= g.rc_2.pwm_out / 2;
-
-		//Front side
-		motor_out[MOT_1]		= g.rc_3.radio_out + g.rc_2.pwm_out;		// CW	 FRONT
-		motor_out[MOT_5] 	= g.rc_3.radio_out + roll_out + pitch_out;	// CCW	 FRONT LEFT
-		motor_out[MOT_4] 	= g.rc_3.radio_out - roll_out + pitch_out;	// CCW	 FRONT RIGHT
-
-		//Back side
-		motor_out[MOT_2]		= g.rc_3.radio_out - g.rc_2.pwm_out;		// CCW	BACK
-		motor_out[MOT_3]		= g.rc_3.radio_out + roll_out - pitch_out;	// CW, 	BACK LEFT
-		motor_out[MOT_6]		= g.rc_3.radio_out - roll_out - pitch_out;	// CW	BACK RIGHT
-	}
-
-	// Yaw
-	motor_out[MOT_2]		+= g.rc_4.pwm_out;	// CCW
-	motor_out[MOT_5]		+= g.rc_4.pwm_out;	// CCW
-	motor_out[MOT_4] 	+= g.rc_4.pwm_out;	// CCW
-
-	motor_out[MOT_3]		-= g.rc_4.pwm_out;	// CW
-	motor_out[MOT_1]		-= g.rc_4.pwm_out;	// CW
-	motor_out[MOT_6]		-= g.rc_4.pwm_out;	// CW
-
-
-	// Tridge's stability patch
-		for (int m = 1; m <= 6; m++){
-			int c = ch_of_mot(m);
-			int c_opp = ch_of_mot(((m-1)^1)+1); // ((m-1)^1)+1 is the opposite motor. c_opp is channel of opposite motor.
-			if(motor_out[c] > out_max){
-				motor_out[c_opp] -= motor_out[c] - out_max;
-				motor_out[c] = out_max;
-			}
-		}
-
-	// limit output so motors don't stop
-	motor_out[MOT_1] = max(motor_out[MOT_1],	out_min);
-	motor_out[MOT_2] = max(motor_out[MOT_2],	out_min);
-	motor_out[MOT_3] = max(motor_out[MOT_3],	out_min);
-	motor_out[MOT_4] = max(motor_out[MOT_4],	out_min);
-	motor_out[MOT_5] = max(motor_out[MOT_5],	out_min);
-	motor_out[MOT_6] = max(motor_out[MOT_6],	out_min);
-
-	#if CUT_MOTORS == ENABLED
-	// if we are not sending a throttle output, we cut the motors
-	if(g.rc_3.servo_out == 0){
-		motor_out[MOT_1]		= g.rc_3.radio_min;
-		motor_out[MOT_2]		= g.rc_3.radio_min;
-		motor_out[MOT_3]		= g.rc_3.radio_min;
-		motor_out[MOT_4] 	= g.rc_3.radio_min;
-		motor_out[MOT_5] 	= g.rc_3.radio_min;
-		motor_out[MOT_6] 	= g.rc_3.radio_min;
-	}
-	#endif
-
-	// this filter slows the acceleration of motors vs the deceleration
-	// Idea by Denny Rowland to help with his Yaw issue
-	for(int8_t m = 1; m <= 6; m++){
-			int c = ch_of_mot(m);
-		if(motor_filtered[c] < motor_out[c]){
-			motor_filtered[c] = (motor_out[c] + motor_filtered[c]) / 2;
-		}else{
-			// don't filter
-			motor_filtered[c] = motor_out[c];
-		}
-	}
-
-	APM_RC.OutputCh(MOT_1, motor_filtered[MOT_1]);
-	APM_RC.OutputCh(MOT_2, motor_filtered[MOT_2]);
-	APM_RC.OutputCh(MOT_3, motor_filtered[MOT_3]);
-	APM_RC.OutputCh(MOT_4, motor_filtered[MOT_4]);
-	APM_RC.OutputCh(MOT_5, motor_filtered[MOT_5]);
-	APM_RC.OutputCh(MOT_6, motor_filtered[MOT_6]);
-
-	#if INSTANT_PWM == 1
-	// InstantPWM
-	APM_RC.Force_Out0_Out1();
-	APM_RC.Force_Out2_Out3();
-	APM_RC.Force_Out6_Out7();
-	#endif
-
-}
-
-static void output_motors_disarmed()
-{
-	if(g.rc_3.control_in > 0){
-		// we have pushed up the throttle
-		// remove safety
-		motor_auto_armed = true;
-	}
-
-	// fill the motor_out[] array for HIL use
-	for (unsigned char i = 0; i < 8; i++){
-		motor_out[i] = g.rc_3.radio_min;
-	}
-
-	// Send commands to motors
-	APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
-}
-
-static void output_motor_test()
-{
-	motors_output_enable();
-
-	motor_out[MOT_1] = g.rc_3.radio_min;
-	motor_out[MOT_2] = g.rc_3.radio_min;
-	motor_out[MOT_3] = g.rc_3.radio_min;
-	motor_out[MOT_4] = g.rc_3.radio_min;
-	motor_out[MOT_5] = g.rc_3.radio_min;
-	motor_out[MOT_6] = g.rc_3.radio_min;
-
-	if(g.frame_orientation == X_FRAME){
-		 APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
-		 delay(4000);
-		 APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
-		 delay(300);
-
-	} else { /* PLUS_FRAME */
-		 APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
-		 delay(4000);
-		 APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100);
-		 delay(300);
-		}
-
-	APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
-	APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
-	APM_RC.OutputCh(MOT_3, motor_out[MOT_3]);
-	APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
-	APM_RC.OutputCh(MOT_5, motor_out[MOT_5]);
-	APM_RC.OutputCh(MOT_6, motor_out[MOT_6]);
-}
-
-#endif
diff --git a/ArduCopter/motors_octa.pde b/ArduCopter/motors_octa.pde
deleted file mode 100644
index 8f552333d27485a5f9fcb42cba8e25f73af1ad1e..0000000000000000000000000000000000000000
--- a/ArduCopter/motors_octa.pde
+++ /dev/null
@@ -1,327 +0,0 @@
-/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
-
-#if FRAME_CONFIG ==	OCTA_FRAME
-
-static void init_motors_out()
-{
-	#if INSTANT_PWM == 0
-	APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4)
-                                 | _BV(MOT_5) | _BV(MOT_6) | _BV(MOT_7) | _BV(MOT_8),
-                                 g.rc_speed);
-	#endif
-}
-
-static void motors_output_enable()
-{
-	APM_RC.enable_out(MOT_1);
-	APM_RC.enable_out(MOT_2);
-	APM_RC.enable_out(MOT_3);
-	APM_RC.enable_out(MOT_4);
-	APM_RC.enable_out(MOT_5);
-	APM_RC.enable_out(MOT_6);
-	APM_RC.enable_out(MOT_7);
-	APM_RC.enable_out(MOT_8);
-}
-
-static void output_motors_armed()
-{
-	int roll_out, pitch_out;
-	int out_min = g.rc_3.radio_min;
-	int out_max = g.rc_3.radio_max;
-
-	// Throttle is 0 to 1000 only
-	g.rc_3.servo_out 	= constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE);
-
-	if(g.rc_3.servo_out > 0)
-		out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
-
-	g.rc_1.calc_pwm();
-	g.rc_2.calc_pwm();
-	g.rc_3.calc_pwm();
-	g.rc_4.calc_pwm();
-
-	if(g.frame_orientation == X_FRAME){
-		roll_out 	 		= (float)g.rc_1.pwm_out * 0.4;
-		pitch_out 	 		= (float)g.rc_2.pwm_out * 0.4;
-
-		//Front side
-		motor_out[MOT_1]	= g.rc_3.radio_out + g.rc_2.pwm_out - roll_out;	 // CW	 FRONT RIGHT
-		motor_out[MOT_5] 	= g.rc_3.radio_out + g.rc_2.pwm_out + roll_out;	 // CCW	 FRONT LEFT
-
-		//Back side
-		motor_out[MOT_2]	= g.rc_3.radio_out - g.rc_2.pwm_out + roll_out;	 // CW	 BACK LEFT
-		motor_out[MOT_4]	= g.rc_3.radio_out - g.rc_2.pwm_out - roll_out;	 // CCW	BACK RIGHT
-
-		//Left side
-		motor_out[MOT_7] 	= g.rc_3.radio_out + g.rc_1.pwm_out + pitch_out; // CW	 LEFT FRONT
-		motor_out[MOT_6] 	= g.rc_3.radio_out + g.rc_1.pwm_out - pitch_out; // CCW	 LEFT BACK
-
-		//Right side
-		motor_out[MOT_8] 	= g.rc_3.radio_out - g.rc_1.pwm_out - pitch_out; // CW	 RIGHT BACK
-		motor_out[MOT_3]	= g.rc_3.radio_out - g.rc_1.pwm_out + pitch_out; // CCW	 RIGHT FRONT
-
-	}else if(g.frame_orientation == PLUS_FRAME){
-		roll_out 			= (float)g.rc_1.pwm_out * 0.71;
-		pitch_out 	 		= (float)g.rc_2.pwm_out * 0.71;
-
-		//Front side
-		motor_out[MOT_1]	= g.rc_3.radio_out + g.rc_2.pwm_out;		// CW	FRONT
-		motor_out[MOT_3] 	= g.rc_3.radio_out - roll_out + pitch_out;	// CCW	FRONT RIGHT
-		motor_out[MOT_5] 	= g.rc_3.radio_out + roll_out + pitch_out;	// CCW	FRONT LEFT
-
-		//Left side
-		motor_out[MOT_7] 	= g.rc_3.radio_out + g.rc_1.pwm_out;		// CW	LEFT
-
-		//Right side
-		motor_out[MOT_8] 	= g.rc_3.radio_out - g.rc_1.pwm_out;		// CW	RIGHT
-
-		//Back side
-		motor_out[MOT_2]	= g.rc_3.radio_out - g.rc_2.pwm_out;		// CW	BACK
-		motor_out[MOT_4]	= g.rc_3.radio_out - roll_out - pitch_out;	// CCW 	BACK RIGHT
-		motor_out[MOT_6]	= g.rc_3.radio_out + roll_out - pitch_out;	// CCW	BACK LEFT
-
-	}else if(g.frame_orientation == V_FRAME){
-
-		int roll_out2, pitch_out2;
-		int roll_out3, pitch_out3;
-		int roll_out4, pitch_out4;
-
-		roll_out 	 	= g.rc_1.pwm_out;
-		pitch_out 	 	= g.rc_2.pwm_out;
-		roll_out2 	 	= (float)g.rc_1.pwm_out * 0.833;
-		pitch_out2 	 	= (float)g.rc_2.pwm_out * 0.34;
-		roll_out3 	 	= (float)g.rc_1.pwm_out * 0.666;
-		pitch_out3 	 	= (float)g.rc_2.pwm_out * 0.32;
-		roll_out4 	 	= g.rc_1.pwm_out / 2;
-		pitch_out4 	 	= (float)g.rc_2.pwm_out * 0.98;
-
-		//Front side
-		motor_out[MOT_7]	= g.rc_3.radio_out + g.rc_2.pwm_out - roll_out;		// CW	FRONT RIGHT
-		motor_out[MOT_5] 	= g.rc_3.radio_out + g.rc_2.pwm_out + roll_out;		// CCW FRONT LEFT
-
-		//Left side
-		motor_out[MOT_1] 	= g.rc_3.radio_out + g.rc_1.pwm_out + pitch_out2; 	// CW	LEFT FRONT
-		motor_out[MOT_3] 	= g.rc_3.radio_out + g.rc_1.pwm_out - pitch_out3;	// CCW LEFT BACK
-
-		//Right side
-		motor_out[MOT_2] 	= g.rc_3.radio_out - g.rc_1.pwm_out - pitch_out3;	// CW	RIGHT BACK
-		motor_out[MOT_6]		= g.rc_3.radio_out - g.rc_1.pwm_out + pitch_out2;	// CCW RIGHT FRONT
-
-		//Back side
-		motor_out[MOT_8]	= g.rc_3.radio_out - g.rc_2.pwm_out + roll_out4;	// CW	BACK LEFT
-		motor_out[MOT_4]	= g.rc_3.radio_out - g.rc_2.pwm_out - roll_out4;	// CCW BACK RIGHT
-
-	}
-
-	// Yaw
-	motor_out[MOT_3]	+= g.rc_4.pwm_out;	// CCW
-	motor_out[MOT_4]	+= g.rc_4.pwm_out;	// CCW
-	motor_out[MOT_5] 	+= g.rc_4.pwm_out;	// CCW
-	motor_out[MOT_6] 	+= g.rc_4.pwm_out;	// CCW
-
-	motor_out[MOT_1]	-= g.rc_4.pwm_out;	// CW
-	motor_out[MOT_2]	-= g.rc_4.pwm_out;	// CW
-	motor_out[MOT_7]	-= g.rc_4.pwm_out;	// CW
-	motor_out[MOT_8]	-= g.rc_4.pwm_out;	// CW
-
-
-	// TODO add stability patch
-	motor_out[MOT_1]		= min(motor_out[MOT_1], out_max);
-	motor_out[MOT_2]		= min(motor_out[MOT_2], out_max);
-	motor_out[MOT_3]		= min(motor_out[MOT_3], out_max);
-	motor_out[MOT_4]		= min(motor_out[MOT_4], out_max);
-	motor_out[MOT_5]		= min(motor_out[MOT_5],	out_max);
-	motor_out[MOT_6]		= min(motor_out[MOT_6],	out_max);
-	motor_out[MOT_7]		= min(motor_out[MOT_7], out_max);
-	motor_out[MOT_8] 		= min(motor_out[MOT_8], out_max);
-
-
-	// limit output so motors don't stop
-	motor_out[MOT_1]		= max(motor_out[MOT_1], out_min);
-	motor_out[MOT_2]		= max(motor_out[MOT_2], out_min);
-	motor_out[MOT_3]		= max(motor_out[MOT_3], out_min);
-	motor_out[MOT_4] 		= max(motor_out[MOT_4], out_min);
-	motor_out[MOT_5]		= max(motor_out[MOT_5], out_min);
-	motor_out[MOT_6]	 	= max(motor_out[MOT_6], out_min);
-	motor_out[MOT_7]		= max(motor_out[MOT_7], out_min);
-	motor_out[MOT_8] 		= max(motor_out[MOT_8], out_min);
-
-
-	#if CUT_MOTORS == ENABLED
-	// if we are not sending a throttle output, we cut the motors
-	if(g.rc_3.servo_out == 0){
-		motor_out[MOT_1]	= g.rc_3.radio_min;
-		motor_out[MOT_2]	= g.rc_3.radio_min;
-		motor_out[MOT_3]	= g.rc_3.radio_min;
-		motor_out[MOT_4] 	= g.rc_3.radio_min;
-		motor_out[MOT_5] 	= g.rc_3.radio_min;
-		motor_out[MOT_6] 	= g.rc_3.radio_min;
-		motor_out[MOT_7] 	= g.rc_3.radio_min;
-		motor_out[MOT_8] 	= g.rc_3.radio_min;
-	}
-	#endif
-
-	// this filter slows the acceleration of motors vs the deceleration
-	// Idea by Denny Rowland to help with his Yaw issue
-	for(int8_t m = 1; m <= 8; m++){
-		int c = ch_of_mot(m);
-		if(motor_filtered[c] < motor_out[c]){
-			motor_filtered[c] = (motor_out[c] + motor_filtered[c]) / 2;
-		}else{
-			// don't filter
-			motor_filtered[c] = motor_out[c];
-		}
-	}
-
-	APM_RC.OutputCh(MOT_1, motor_filtered[MOT_1]);
-	APM_RC.OutputCh(MOT_2, motor_filtered[MOT_2]);
-	APM_RC.OutputCh(MOT_3, motor_filtered[MOT_3]);
-	APM_RC.OutputCh(MOT_4, motor_filtered[MOT_4]);
-	APM_RC.OutputCh(MOT_5, motor_filtered[MOT_5]);
-	APM_RC.OutputCh(MOT_6, motor_filtered[MOT_6]);
-	APM_RC.OutputCh(MOT_7, motor_filtered[MOT_7]);
-	APM_RC.OutputCh(MOT_8, motor_filtered[MOT_8]);
-
-	#if INSTANT_PWM == 1
-	// InstantPWM
-	APM_RC.Force_Out0_Out1();
-	APM_RC.Force_Out2_Out3();
-	APM_RC.Force_Out6_Out7();
-	#endif
-}
-
-static void output_motors_disarmed()
-{
-	if(g.rc_3.control_in > 0){
-		// we have pushed up the throttle
-		// remove safety
-		motor_auto_armed = true;
-	}
-
-	// fill the motor_out[] array for HIL use
-	for (unsigned char i = 0; i < 11; i++){
-		motor_out[i] = g.rc_3.radio_min;
-	}
-
-	// Send commands to motors
-	APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_8, g.rc_3.radio_min);
-
-	APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_7, g.rc_3.radio_min);
-}
-
-static void output_motor_test()
-{
-
-		motor_out[MOT_1] = g.rc_3.radio_min;
-		motor_out[MOT_2] = g.rc_3.radio_min;
-		motor_out[MOT_3] = g.rc_3.radio_min;
-		motor_out[MOT_4] = g.rc_3.radio_min;
-		motor_out[MOT_5] = g.rc_3.radio_min;
-		motor_out[MOT_6] = g.rc_3.radio_min;
-		motor_out[MOT_7] = g.rc_3.radio_min;
-		motor_out[MOT_8] = g.rc_3.radio_min;
-
-
-	if(g.frame_orientation == X_FRAME || g.frame_orientation == PLUS_FRAME){
-		 APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
-		 delay(4000);
-		 APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_8, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_8, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_7, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_7, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100);
-		 delay(300);
-	}
-
-	if(g.frame_orientation == V_FRAME){
-		 APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
-		 delay(4000);
-		 APM_RC.OutputCh(MOT_7, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_7, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_8, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_8, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100);
-		 delay(300);
-	}
-
-	APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
-	APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
-	APM_RC.OutputCh(MOT_3, motor_out[MOT_3]);
-	APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
-	APM_RC.OutputCh(MOT_5, motor_out[MOT_5]);
-	APM_RC.OutputCh(MOT_6, motor_out[MOT_6]);
-	APM_RC.OutputCh(MOT_7, motor_out[MOT_7]);
-	APM_RC.OutputCh(MOT_8, motor_out[MOT_8]);
-
-}
-
-#endif
-
diff --git a/ArduCopter/motors_octa_quad.pde b/ArduCopter/motors_octa_quad.pde
deleted file mode 100644
index 3032c6d82ac50efa341b5f7b7c7df9d41a2649d5..0000000000000000000000000000000000000000
--- a/ArduCopter/motors_octa_quad.pde
+++ /dev/null
@@ -1,227 +0,0 @@
-/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
-
-#if FRAME_CONFIG ==	OCTA_QUAD_FRAME
-
-static void init_motors_out()
-{
-	#if INSTANT_PWM == 0
-	APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4)
-                                 | _BV(MOT_5) | _BV(MOT_6) | _BV(MOT_7) | _BV(MOT_8),
-                                 g.rc_speed);
-	#endif
-}
-
-static void motors_output_enable()
-{
-	APM_RC.enable_out(MOT_1);
-	APM_RC.enable_out(MOT_2);
-	APM_RC.enable_out(MOT_3);
-	APM_RC.enable_out(MOT_4);
-	APM_RC.enable_out(MOT_5);
-	APM_RC.enable_out(MOT_6);
-	APM_RC.enable_out(MOT_7);
-	APM_RC.enable_out(MOT_8);
-}
-
-static void output_motors_armed()
-{
-	int roll_out, pitch_out;
-	int out_min = g.rc_3.radio_min;
-	int out_max = g.rc_3.radio_max;
-
-	// Throttle is 0 to 1000 only
-	g.rc_3.servo_out 	= constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE);
-
-	if(g.rc_3.servo_out > 0)
-		out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
-
-	g.rc_1.calc_pwm();
-	g.rc_2.calc_pwm();
-	g.rc_3.calc_pwm();
-	g.rc_4.calc_pwm();
-
-	if(g.frame_orientation == X_FRAME){
-		roll_out		= (float)g.rc_1.pwm_out * 0.707;
-		pitch_out		= (float)g.rc_2.pwm_out * 0.707;
-
-		motor_out[MOT_1]		= ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out + pitch_out);		//	APM2 OUT1	APM1 OUT1	 FRONT RIGHT	CCW		TOP
-		motor_out[MOT_2]		= ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out + pitch_out);		//	APM2 OUT2	APM1 OUT2	 FRONT LEFT		CW		TOP
-		motor_out[MOT_3]		= ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out - pitch_out);		//	APM2 OUT3	APM1 OUT3	 BACK LEFT		CCW		TOP
-		motor_out[MOT_4]		= ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out - pitch_out);		//	APM2 OUT4	APM1 OUT4	 BACK RIGHT		CW		TOP
-		motor_out[MOT_5]		=	g.rc_3.radio_out + roll_out + pitch_out;								//	APM2 OUT5	APM1 OUT7	 FRONT LEFT		CCW		BOTTOM
-		motor_out[MOT_6]		=	g.rc_3.radio_out - roll_out + pitch_out;								//	APM2 OUT6	APM1 OUT8	 FRONT RIGHT	CW		BOTTOM
-		motor_out[MOT_7]		=	g.rc_3.radio_out - roll_out - pitch_out;								//	APM2 OUT7	APM1 OUT10	 BACK RIGHT		CCW		BOTTOM
-		motor_out[MOT_8]		=	g.rc_3.radio_out + roll_out - pitch_out;								//	APM2 OUT8	APM1 OUT11	 BACK LEFT		CW		BOTTOM
-	}else{
-		roll_out 	 			= g.rc_1.pwm_out;
-		pitch_out 	 			= g.rc_2.pwm_out;
-
-		motor_out[MOT_1]		= (g.rc_3.radio_out * g.top_bottom_ratio) + pitch_out;	// APM2 OUT1		APM1 OUT1		FRONT	CCW		TOP
-		motor_out[MOT_2]		= (g.rc_3.radio_out * g.top_bottom_ratio) + roll_out;	// APM2 OUT2		APM1 OUT2		LEFT	CW		TOP
-		motor_out[MOT_3]		= (g.rc_3.radio_out * g.top_bottom_ratio) - pitch_out;	// APM2 OUT3		APM1 OUT3		BACK	CCW		TOP
-		motor_out[MOT_4]		= (g.rc_3.radio_out * g.top_bottom_ratio) - roll_out;	// APM2 OUT4		APM1 OUT4		RIGHT	CW		TOP
-		motor_out[MOT_5]		= g.rc_3.radio_out + roll_out;							// APM2 OUT5		APM1 OUT7		LEFT	CCW		BOTTOM
-		motor_out[MOT_6]		= g.rc_3.radio_out + pitch_out;						// APM2 OUT6		APM1 OUT8		FRONT	CW		BOTTOM
-		motor_out[MOT_7]		= g.rc_3.radio_out - roll_out;							// APM2 OUT7		APM1 OUT10		RIGHT	CCW		BOTTOM
-		motor_out[MOT_8]		= g.rc_3.radio_out - pitch_out;						// APM2 OUT8		APM1 OUT11		BACK	CW		BOTTOM
-	}
-
-	// Yaw
-	motor_out[MOT_1]		+= g.rc_4.pwm_out;	// CCW
-	motor_out[MOT_3]		+= g.rc_4.pwm_out;	// CCW
-	motor_out[MOT_5]		+= g.rc_4.pwm_out;	// CCW
-	motor_out[MOT_7]		+= g.rc_4.pwm_out;	// CCW
-
-	motor_out[MOT_2]		-= g.rc_4.pwm_out;	// CW
-	motor_out[MOT_4]		-= g.rc_4.pwm_out;	// CW
-	motor_out[MOT_6]		-= g.rc_4.pwm_out;	// CW
-	motor_out[MOT_8]		-= g.rc_4.pwm_out;	// CW
-
-	// TODO add stability patch
-	motor_out[MOT_1]		= min(motor_out[MOT_1], out_max);
-	motor_out[MOT_2]		= min(motor_out[MOT_2], out_max);
-	motor_out[MOT_3]		= min(motor_out[MOT_3], out_max);
-	motor_out[MOT_4]		= min(motor_out[MOT_4], out_max);
-	motor_out[MOT_5]		= min(motor_out[MOT_5],	out_max);
-	motor_out[MOT_6]		= min(motor_out[MOT_6],	out_max);
-	motor_out[MOT_7]		= min(motor_out[MOT_7], out_max);
-	motor_out[MOT_8] 		= min(motor_out[MOT_8], out_max);
-
-	// limit output so motors don't stop
-	motor_out[MOT_1]		= max(motor_out[MOT_1], 	out_min);
-	motor_out[MOT_2]		= max(motor_out[MOT_2], 	out_min);
-	motor_out[MOT_3]		= max(motor_out[MOT_3], 	out_min);
-	motor_out[MOT_4] 		= max(motor_out[MOT_4], 	out_min);
-	motor_out[MOT_5]		= max(motor_out[MOT_5], 	out_min);
-	motor_out[MOT_6] 		= max(motor_out[MOT_6], 	out_min);
-	motor_out[MOT_7]		= max(motor_out[MOT_7], out_min);
-	motor_out[MOT_8] 		= max(motor_out[MOT_8], out_min);
-
-	#if CUT_MOTORS == ENABLED
-	// if we are not sending a throttle output, we cut the motors
-	if(g.rc_3.servo_out == 0){
-		motor_out[MOT_1]	= g.rc_3.radio_min;
-		motor_out[MOT_2]	= g.rc_3.radio_min;
-		motor_out[MOT_3]	= g.rc_3.radio_min;
-		motor_out[MOT_4] 	= g.rc_3.radio_min;
-		motor_out[MOT_5] 	= g.rc_3.radio_min;
-		motor_out[MOT_6] 	= g.rc_3.radio_min;
-		motor_out[MOT_7] 	= g.rc_3.radio_min;
-		motor_out[MOT_8] 	= g.rc_3.radio_min;
-	}
-	#endif
-
-	// this filter slows the acceleration of motors vs the deceleration
-	// Idea by Denny Rowland to help with his Yaw issue
-	for(int8_t m = 1; m <= 8; m++){
-		int i = ch_of_mot(m);
-		if(motor_filtered[i] < motor_out[i]){
-			motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2;
-		}else{
-			// don't filter
-			motor_filtered[i] = motor_out[i];
-		}
-	}
-
-	APM_RC.OutputCh(MOT_1, motor_filtered[MOT_1]);
-	APM_RC.OutputCh(MOT_2, motor_filtered[MOT_2]);
-	APM_RC.OutputCh(MOT_3, motor_filtered[MOT_3]);
-	APM_RC.OutputCh(MOT_4, motor_filtered[MOT_4]);
-	APM_RC.OutputCh(MOT_5, motor_filtered[MOT_5]);
-	APM_RC.OutputCh(MOT_6, motor_filtered[MOT_6]);
-	APM_RC.OutputCh(MOT_7, motor_filtered[MOT_7]);
-	APM_RC.OutputCh(MOT_8, motor_filtered[MOT_8]);
-
-	#if INSTANT_PWM == 1
-	// InstantPWM
-	APM_RC.Force_Out0_Out1();
-	APM_RC.Force_Out2_Out3();
-	APM_RC.Force_Out6_Out7();
-	#endif
-}
-
-static void output_motors_disarmed()
-{
-	if(g.rc_3.control_in > 0){
-		// we have pushed up the throttle
-		// remove safety
-		motor_auto_armed = true;
-	}
-
-	// fill the motor_out[] array for HIL use
-	for (unsigned char i = 0; i < 11; i++){
-		motor_out[i] = g.rc_3.radio_min;
-	}
-
-	// Send commands to motors
-	APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_7, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_8, g.rc_3.radio_min);
-}
-
-static void output_motor_test()
-{
-	motor_out[MOT_1] = g.rc_3.radio_min;
-	motor_out[MOT_2] = g.rc_3.radio_min;
-	motor_out[MOT_3] = g.rc_3.radio_min;
-	motor_out[MOT_4] = g.rc_3.radio_min;
-	motor_out[MOT_5] = g.rc_3.radio_min;
-	motor_out[MOT_6] = g.rc_3.radio_min;
-	motor_out[MOT_7] = g.rc_3.radio_min;
-	motor_out[MOT_8] = g.rc_3.radio_min;
-
-	APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
-	delay(5000);
-	APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
-	delay(300);
-
-	APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
-	delay(3000);
-	APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100);
-	delay(300);
-
-	APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
-	delay(3000);
-	APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100);
-	delay(300);
-
-	APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
-	delay(3000);
-	APM_RC.OutputCh(MOT_7, g.rc_3.radio_min + 100);
-	delay(300);
-
-	APM_RC.OutputCh(MOT_7, g.rc_3.radio_min);
-	delay(3000);
-	APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
-	delay(300);
-
-	APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
-	delay(3000);
-	APM_RC.OutputCh(MOT_8, g.rc_3.radio_min + 100);
-	delay(300);
-
-	APM_RC.OutputCh(MOT_8, g.rc_3.radio_min);
-	delay(3000);
-	APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100);
-	delay(300);
-
-	APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
-	delay(3000);
-	APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100);
-	delay(300);
-
-	APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
-	APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
-	APM_RC.OutputCh(MOT_3, motor_out[MOT_3]);
-	APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
-	APM_RC.OutputCh(MOT_5, motor_out[MOT_5]);
-	APM_RC.OutputCh(MOT_6, motor_out[MOT_6]);
-	APM_RC.OutputCh(MOT_7, motor_out[MOT_7]);
-	APM_RC.OutputCh(MOT_8, motor_out[MOT_8]);
-}
-#endif
diff --git a/ArduCopter/motors_quad.pde b/ArduCopter/motors_quad.pde
deleted file mode 100644
index fc509965850a62319cd0526eda24d4dd465626f5..0000000000000000000000000000000000000000
--- a/ArduCopter/motors_quad.pde
+++ /dev/null
@@ -1,209 +0,0 @@
-/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
-
-#if FRAME_CONFIG ==	QUAD_FRAME
-
-static void init_motors_out()
-{
-	#if INSTANT_PWM == 0
-	APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4),
-                                 g.rc_speed);
-	#endif
-}
-
-static void motors_output_enable()
-{
-	APM_RC.enable_out(MOT_1);
-	APM_RC.enable_out(MOT_2);
-	APM_RC.enable_out(MOT_3);
-	APM_RC.enable_out(MOT_4);
-}
-
-static void output_motors_armed()
-{
-	int roll_out, pitch_out;
-	int out_min = g.rc_3.radio_min;
-	int out_max = g.rc_3.radio_max;
-
-	// Throttle is 0 to 1000 only
-	g.rc_3.servo_out 	= constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE);
-
-	if(g.rc_3.servo_out > 0)
-		out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
-
-	g.rc_1.calc_pwm();
-	g.rc_2.calc_pwm();
-	g.rc_3.calc_pwm();
-	g.rc_4.calc_pwm();
-
-
-
-	if(g.frame_orientation == X_FRAME){
-		roll_out 	 	= (float)g.rc_1.pwm_out * 0.707;
-		pitch_out 	 	= (float)g.rc_2.pwm_out * 0.707;
-
-		// left
-		motor_out[MOT_3]	= g.rc_3.radio_out + roll_out + pitch_out;	// FRONT
-		motor_out[MOT_2]	= g.rc_3.radio_out + roll_out - pitch_out;	// BACK
-
-		// right
-		motor_out[MOT_1]	= g.rc_3.radio_out - roll_out + pitch_out;	// FRONT
-		motor_out[MOT_4] 	= g.rc_3.radio_out - roll_out - pitch_out;	// BACK
-
-	}else{
-
-		roll_out 	 	= g.rc_1.pwm_out;
-		pitch_out 	 	= g.rc_2.pwm_out;
-
-		// right motor
-		motor_out[MOT_1]	= g.rc_3.radio_out - roll_out;
-		// left motor
-		motor_out[MOT_2]	= g.rc_3.radio_out + roll_out;
-		// front motor
-		motor_out[MOT_3]	= g.rc_3.radio_out + pitch_out;
-		// back motor
-		motor_out[MOT_4] 	= g.rc_3.radio_out - pitch_out;
-	}
-
-	// Yaw input
-	motor_out[MOT_1]	+=	g.rc_4.pwm_out; 	// CCW
-	motor_out[MOT_2]	+=	g.rc_4.pwm_out; 	// CCW
-	motor_out[MOT_3]	-=	g.rc_4.pwm_out; 	// CW
-	motor_out[MOT_4] 	-=	g.rc_4.pwm_out; 	// CW
-
-    /* We need to clip motor output at out_max. When cipping a motors
-		 * output we also need to compensate for the instability by
-		 * lowering the opposite motor by the same proportion. This
-		 * ensures that we retain control when one or more of the motors
-		 * is at its maximum output
-		 */
-		for (int i = MOT_1; i <= MOT_4; i++){
-				if(motor_out[i] > out_max){
-		            // note that i^1 is the opposite motor
-					motor_out[i ^ 1] -= motor_out[i] - out_max;
-					motor_out[i] = out_max;
-				}
-		}
-
-	// limit output so motors don't stop
-	motor_out[MOT_1]	= max(motor_out[MOT_1], 	out_min);
-	motor_out[MOT_2]	= max(motor_out[MOT_2], 	out_min);
-	motor_out[MOT_3]	= max(motor_out[MOT_3], 	out_min);
-	motor_out[MOT_4] 	= max(motor_out[MOT_4], 	out_min);
-
-	#if CUT_MOTORS == ENABLED
-	// if we are not sending a throttle output, we cut the motors
-	if(g.rc_3.servo_out == 0){
-		motor_out[MOT_1]	= g.rc_3.radio_min;
-		motor_out[MOT_2]	= g.rc_3.radio_min;
-		motor_out[MOT_3]	= g.rc_3.radio_min;
-		motor_out[MOT_4] 	= g.rc_3.radio_min;
-	}
-	#endif
-
-	APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
-	APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
-	APM_RC.OutputCh(MOT_3, motor_out[MOT_3]);
-	APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
-
-
-	#if INSTANT_PWM == 1
-	// InstantPWM
-	APM_RC.Force_Out0_Out1();
-	APM_RC.Force_Out2_Out3();
-	#endif
-
-	//debug_motors();
-}
-
-static void output_motors_disarmed()
-{
-	if(g.rc_3.control_in > 0){
-		// we have pushed up the throttle
-		// remove safety
-		motor_auto_armed = true;
-	}
-
-	// fill the motor_out[] array for HIL use
-	for (unsigned char i = 0; i < 8; i++){
-		motor_out[i] = g.rc_3.radio_min;
-	}
-
-	// Send commands to motors
-	APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
-}
-
-/*
-//static void debug_motors()
-{
-	Serial.printf("1:%d\t2:%d\t3:%d\t4:%d\n",
-				motor_out[MOT_1],
-				motor_out[MOT_2],
-				motor_out[MOT_3],
-				motor_out[MOT_4]);
-}
-//*/
-
-static void output_motor_test()
-{
-	motor_out[MOT_1] = g.rc_3.radio_min;
-	motor_out[MOT_2] = g.rc_3.radio_min;
-	motor_out[MOT_3] = g.rc_3.radio_min;
-	motor_out[MOT_4] = g.rc_3.radio_min;
-
-
-	if(g.frame_orientation == X_FRAME){
-
-		 APM_RC.OutputCh(MOT_3, g.rc_2.radio_min);
-		 delay(4000);
-		 APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_4, g.rc_1.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_4, g.rc_1.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_2, g.rc_4.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_2, g.rc_4.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_3, g.rc_2.radio_min + 100);
-		 delay(300);
-
-	}else{
-
-		 APM_RC.OutputCh(MOT_2, g.rc_2.radio_min);
-		 delay(4000);
-		 APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_1, g.rc_1.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_1, g.rc_1.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_4, g.rc_4.radio_min + 100);
-		 delay(300);
-
-		 APM_RC.OutputCh(MOT_4, g.rc_4.radio_min);
-		 delay(2000);
-		 APM_RC.OutputCh(MOT_2, g.rc_2.radio_min + 100);
-		 delay(300);
-
-	}
-
-	APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
-	APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
-	APM_RC.OutputCh(MOT_3, motor_out[MOT_3]);
-	APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
-}
-
-#endif
diff --git a/ArduCopter/motors_tri.pde b/ArduCopter/motors_tri.pde
deleted file mode 100644
index 9371201557d0bd8f2196ce60c0e9e0e7f918c8f1..0000000000000000000000000000000000000000
--- a/ArduCopter/motors_tri.pde
+++ /dev/null
@@ -1,137 +0,0 @@
-/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
-#if FRAME_CONFIG ==	TRI_FRAME
-
-static void init_motors_out()
-{
-	#if INSTANT_PWM == 0
-    APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_4),
-                                 g.rc_speed);
-	#endif
-}
-
-static void motors_output_enable()
-{
-	APM_RC.enable_out(MOT_1);
-	APM_RC.enable_out(MOT_2);
-	APM_RC.enable_out(MOT_4);
-	APM_RC.enable_out(CH_TRI_YAW);
-}
-
-
-static void output_motors_armed()
-{
-	int out_min = g.rc_3.radio_min;
-	int out_max = g.rc_3.radio_max;
-
-	// Throttle is 0 to 1000 only
-	g.rc_3.servo_out 	= constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE);
-
-	if(g.rc_3.servo_out > 0)
-		out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
-
-	g.rc_1.calc_pwm();
-	g.rc_2.calc_pwm();
-	g.rc_3.calc_pwm();
-
-	int roll_out 		= (float)g.rc_1.pwm_out * .866;
-	int pitch_out 		= g.rc_2.pwm_out / 2;
-
-	//left front
-	motor_out[MOT_2]		= g.rc_3.radio_out + roll_out + pitch_out;
-	//right front
-	motor_out[MOT_1]		= g.rc_3.radio_out - roll_out + pitch_out;
-	// rear
-	motor_out[MOT_4] 	= g.rc_3.radio_out - g.rc_2.pwm_out;
-
-	//motor_out[MOT_4]		+= (float)(abs(g.rc_4.control_in)) * .013;
-
-	// Tridge's stability patch
-	if(motor_out[MOT_1] > out_max){
-		motor_out[MOT_2] -= (motor_out[MOT_1] - out_max) >> 1;
-		motor_out[MOT_4] -= (motor_out[MOT_1] - out_max) >> 1;
-		motor_out[MOT_1] = out_max;
-	}
-
-	if(motor_out[MOT_2] > out_max){
-		motor_out[MOT_1] -= (motor_out[MOT_2] - out_max) >> 1;
-		motor_out[MOT_4] -= (motor_out[MOT_2] - out_max) >> 1;
-		motor_out[MOT_2] = out_max;
-	}
-
-	if(motor_out[MOT_4] > out_max){
-		motor_out[MOT_1] -= (motor_out[MOT_4] - out_max) >> 1;
-		motor_out[MOT_2] -= (motor_out[MOT_4] - out_max) >> 1;
-		motor_out[MOT_4] = out_max;
-	}
-
-	// limit output so motors don't stop
-	motor_out[MOT_1]		= max(motor_out[MOT_1], 	out_min);
-	motor_out[MOT_2]		= max(motor_out[MOT_2], 	out_min);
-	motor_out[MOT_4] 	= max(motor_out[MOT_4], 	out_min);
-
-	#if CUT_MOTORS == ENABLED
-	// if we are not sending a throttle output, we cut the motors
-	if(g.rc_3.servo_out == 0){
-		motor_out[MOT_1]		= g.rc_3.radio_min;
-		motor_out[MOT_2]		= g.rc_3.radio_min;
-		motor_out[MOT_4] 	= g.rc_3.radio_min;
-	}
-	#endif
-
-	APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
-	APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
-	APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
-
-	#if INSTANT_PWM == 1
-	// InstantPWM
-	APM_RC.Force_Out0_Out1();
-	APM_RC.Force_Out2_Out3();
-	#endif
-}
-
-static void output_motors_disarmed()
-{
-	if(g.rc_3.control_in > 0){
-		// we have pushed up the throttle
-		// remove safety
-		motor_auto_armed = true;
-	}
-
-	// fill the motor_out[] array for HIL use
-	for (unsigned char i = 0; i < 8; i++){
-		motor_out[i] = g.rc_3.radio_min;
-	}
-
-	// Send commands to motors
-	APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
-}
-
-static void output_motor_test()
-{
-	motor_out[MOT_1] = g.rc_3.radio_min;
-	motor_out[MOT_2] = g.rc_3.radio_min;
-	motor_out[MOT_4] = g.rc_3.radio_min;
-
-	 APM_RC.OutputCh(MOT_2, g.rc_2.radio_min);
-	delay(4000);
-	APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
-	delay(300);
-
-	APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
-	delay(2000);
-	APM_RC.OutputCh(MOT_4, g.rc_1.radio_min + 100);
-	delay(300);
-
-	APM_RC.OutputCh(MOT_4, g.rc_1.radio_min);
-	delay(2000);
-	APM_RC.OutputCh(MOT_2, g.rc_4.radio_min + 100);
-	delay(300);
-
-	APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
-	APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
-	APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
-}
-
-#endif
diff --git a/ArduCopter/motors_y6.pde b/ArduCopter/motors_y6.pde
deleted file mode 100644
index a86d63ec6abcef7f4d332b5e7f56c87ea2877391..0000000000000000000000000000000000000000
--- a/ArduCopter/motors_y6.pde
+++ /dev/null
@@ -1,216 +0,0 @@
-/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
-
-#if FRAME_CONFIG ==	Y6_FRAME
-
-#define YAW_DIRECTION 1
-
-static void init_motors_out()
-{
-	#if INSTANT_PWM == 0
-		APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4)
-                                     | _BV(MOT_5) | _BV(MOT_6),
-                                     g.rc_speed);
-	#endif
-}
-
-static void motors_output_enable()
-{
-	APM_RC.enable_out(MOT_1);
-	APM_RC.enable_out(MOT_2);
-	APM_RC.enable_out(MOT_3);
-	APM_RC.enable_out(MOT_4);
-	APM_RC.enable_out(MOT_5);
-	APM_RC.enable_out(MOT_6);
-}
-
-static void output_motors_armed()
-{
-	int out_min = g.rc_3.radio_min;
-	int out_max = g.rc_3.radio_max;
-
-	// Throttle is 0 to 1000 only
-	g.rc_3.servo_out 	= constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE);
-
-	if(g.rc_3.servo_out > 0)
-		out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
-
-	g.rc_1.calc_pwm();
-	g.rc_2.calc_pwm();
-	g.rc_3.calc_pwm();
-	g.rc_4.calc_pwm();
-
-	// Multi-Wii Mix
-	//left
-	motor_out[MOT_2] 		= (g.rc_3.radio_out * g.top_bottom_ratio) + g.rc_1.pwm_out + (g.rc_2.pwm_out * 2 / 3); // LEFT	 TOP - CW
-	motor_out[MOT_3] 		= g.rc_3.radio_out + g.rc_1.pwm_out	+ (g.rc_2.pwm_out * 2 / 3); // BOTTOM_LEFT - CCW
-	//right
-	motor_out[MOT_5] 		= (g.rc_3.radio_out * g.top_bottom_ratio) - g.rc_1.pwm_out + (g.rc_2.pwm_out * 2 / 3); // RIGHT TOP - CW
-	motor_out[MOT_1] 		= g.rc_3.radio_out - g.rc_1.pwm_out + (g.rc_2.pwm_out * 2 / 3); // BOTTOM_RIGHT - CCW
-	//back
-	motor_out[MOT_6] 		= (g.rc_3.radio_out * g.top_bottom_ratio) - (g.rc_2.pwm_out * 4 / 3); 					// REAR TOP - CCW
-	motor_out[MOT_4] 		= g.rc_3.radio_out - (g.rc_2.pwm_out * 4 / 3); 					// BOTTOM_REAR - CW
-
-	//left
-	motor_out[MOT_2] 		-= YAW_DIRECTION * g.rc_4.pwm_out; // LEFT TOP - CW
-	motor_out[MOT_3] 		+= YAW_DIRECTION * g.rc_4.pwm_out; // LEFT BOTTOM - CCW
-	//right
-	motor_out[MOT_5] 		-= YAW_DIRECTION * g.rc_4.pwm_out; // RIGHT TOP - CW
-	motor_out[MOT_1] 		+= YAW_DIRECTION * g.rc_4.pwm_out; // RIGHT BOTTOM - CCW
-	//back
-	motor_out[MOT_6] 		+= YAW_DIRECTION * g.rc_4.pwm_out; // REAR TOP - CCW
-	motor_out[MOT_4] 		-= YAW_DIRECTION * g.rc_4.pwm_out; // REAR BOTTOM - CW
-
-
-	/*
-	int roll_out 		= (float)g.rc_1.pwm_out * .866;
-	int pitch_out 		=	g.rc_2.pwm_out / 2;
-
-	//left
-	motor_out[MOT_2]		= ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out + pitch_out);	// CCW TOP
-	motor_out[MOT_3]		=	g.rc_3.radio_out + roll_out + pitch_out;							// CW
-
-	//right
-	motor_out[MOT_5]		= ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out + pitch_out);	// CCW TOP
-	motor_out[MOT_1]		=	g.rc_3.radio_out - roll_out + pitch_out;							// CW
-
-	//back
-	motor_out[MOT_6]		 = ((g.rc_3.radio_out * g.top_bottom_ratio) - g.rc_2.pwm_out);		// CCW TOP
-	motor_out[MOT_4] 	=	g.rc_3.radio_out - g.rc_2.pwm_out;								// CW
-
-	// Yaw
-	//top
-	motor_out[MOT_2]		+= g.rc_4.pwm_out;	// CCW
-	motor_out[MOT_5]		+= g.rc_4.pwm_out;	// CCW
-	motor_out[MOT_6] 	+= g.rc_4.pwm_out;	// CCW
-
-	//bottom
-	motor_out[MOT_3]		-= g.rc_4.pwm_out;	// CW
-	motor_out[MOT_1]		-= g.rc_4.pwm_out;	// CW
-	motor_out[MOT_4]		-= g.rc_4.pwm_out;	// CW
-	*/
-
-	// TODO: add stability patch
-	motor_out[MOT_1]	= min(motor_out[MOT_1], 	out_max);
-	motor_out[MOT_2]	= min(motor_out[MOT_2], 	out_max);
-	motor_out[MOT_3]	= min(motor_out[MOT_3], 	out_max);
-	motor_out[MOT_4] = min(motor_out[MOT_4], 	out_max);
-	motor_out[MOT_5] = min(motor_out[MOT_5],	out_max);
-	motor_out[MOT_6]	= min(motor_out[MOT_6],	out_max);
-
-	// limit output so motors don't stop
-	motor_out[MOT_1] = max(motor_out[MOT_1],	out_min);
-	motor_out[MOT_2] = max(motor_out[MOT_2],	out_min);
-	motor_out[MOT_3] = max(motor_out[MOT_3],	out_min);
-	motor_out[MOT_4] = max(motor_out[MOT_4],	out_min);
-	motor_out[MOT_5] = max(motor_out[MOT_5],	out_min);
-	motor_out[MOT_6] = max(motor_out[MOT_6],	out_min);
-
-	#if CUT_MOTORS == ENABLED
-	// if we are not sending a throttle output, we cut the motors
-	if(g.rc_3.servo_out == 0){
-		motor_out[MOT_1]		= g.rc_3.radio_min;
-		motor_out[MOT_2]		= g.rc_3.radio_min;
-		motor_out[MOT_3]		= g.rc_3.radio_min;
-		motor_out[MOT_4] 	= g.rc_3.radio_min;
-		motor_out[MOT_5] 	= g.rc_3.radio_min;
-		motor_out[MOT_6] 	= g.rc_3.radio_min;
-	}
-	#endif
-
-	// this filter slows the acceleration of motors vs the deceleration
-	// Idea by Denny Rowland to help with his Yaw issue
-	for(int8_t m = 1; m <= 6; m++){
-		int i = ch_of_mot(m);
-		if(motor_filtered[i] < motor_out[i]){
-			motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2;
-		}else{
-			// don't filter
-			motor_filtered[i] = motor_out[i];
-		}
-	}
-
-	APM_RC.OutputCh(MOT_1, motor_filtered[MOT_1]);
-	APM_RC.OutputCh(MOT_2, motor_filtered[MOT_2]);
-	APM_RC.OutputCh(MOT_3, motor_filtered[MOT_3]);
-	APM_RC.OutputCh(MOT_4, motor_filtered[MOT_4]);
-	APM_RC.OutputCh(MOT_5, motor_filtered[MOT_5]);
-	APM_RC.OutputCh(MOT_6, motor_filtered[MOT_6]);
-
-	#if INSTANT_PWM == 1
-	// InstantPWM
-	APM_RC.Force_Out0_Out1();
-	APM_RC.Force_Out2_Out3();
-	APM_RC.Force_Out6_Out7();
-	#endif
-}
-
-static void output_motors_disarmed()
-{
-	if(g.rc_3.control_in > 0){
-		// we have pushed up the throttle
-		// remove safety
-		motor_auto_armed = true;
-	}
-
-	// fill the motor_out[] array for HIL use
-	for (unsigned char i = 0; i < 8; i++){
-		motor_out[i] = g.rc_3.radio_min;
-	}
-
-	// Send commands to motors
-	APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
-}
-
-static void output_motor_test()
-{
-	motor_out[MOT_1] = g.rc_3.radio_min;
-	motor_out[MOT_2] = g.rc_3.radio_min;
-	motor_out[MOT_3] = g.rc_3.radio_min;
-	motor_out[MOT_4] = g.rc_3.radio_min;
-	motor_out[MOT_5] = g.rc_3.radio_min;
-	motor_out[MOT_6] = g.rc_3.radio_min;
-
-	APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
-	delay(5000);
-	APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100);
-	delay(300);
-
-	APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
-	delay(3000);
-	APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
-	delay(300);
-
-	APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
-	delay(3000);
-	APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100);
-	delay(300);
-
-	APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
-	delay(3000);
-	APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100);
-	delay(300);
-
-	APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
-	delay(3000);
-	APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100);
-	delay(300);
-
-	APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
-	delay(3000);
-	APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
-	delay(300);
-
-	APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
-	APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
-	APM_RC.OutputCh(MOT_3, motor_out[MOT_4]);
-	APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
-	APM_RC.OutputCh(MOT_5, motor_out[MOT_5]);
-	APM_RC.OutputCh(MOT_6, motor_out[MOT_6]);
-}
-
-#endif
diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde
index 7e9ec6de27c77412cf1123ad3d2088029dc26395..1fc97371bca96b3be5fbd3a6f63ca9f3de8f1586 100644
--- a/ArduCopter/radio.pde
+++ b/ArduCopter/radio.pde
@@ -47,7 +47,15 @@ static void init_rc_in()
 static void init_rc_out()
 {
 	APM_RC.Init( &isr_registry );		// APM Radio initialization
-	init_motors_out();
+	#if INSTANT_PWM == 1
+	motors.set_update_rate(AP_MOTORS_SPEED_INSTANT_PWM);
+	#else
+	motors.set_update_rate(g.rc_speed);
+	#endif
+	motors.set_frame_orientation(g.frame_orientation);
+	motors.Init();						// motor initialisation
+	motors.set_min_throttle(MINIMUM_THROTTLE);
+	motors.set_max_throttle(MAXIMUM_THROTTLE);
 
 	// this is the camera pitch5 and roll6
 	APM_RC.OutputCh(CH_CAM_PITCH, 1500);
@@ -69,7 +77,7 @@ static void init_rc_out()
 			// we will enter esc_calibrate mode on next reboot
 			g.esc_calibrate.set_and_save(1);
 			// send miinimum throttle out to ESC
-			output_min();
+			motors.output_min();
 			// block until we restart
 			while(1){
 				//Serial.println("esc");
@@ -95,28 +103,8 @@ static void init_rc_out()
 
 void output_min()
 {
-	motors_output_enable();
-	#if FRAME_CONFIG == HELI_FRAME
-        heli_move_servos_to_mid();
-	#else
-	    APM_RC.OutputCh(MOT_1, 	g.rc_3.radio_min);					// Initialization of servo outputs
-	    APM_RC.OutputCh(MOT_2, 	g.rc_3.radio_min);
-	    APM_RC.OutputCh(MOT_3, 	g.rc_3.radio_min);
-	    APM_RC.OutputCh(MOT_4, 	g.rc_3.radio_min);
-	#endif
-
-	APM_RC.OutputCh(MOT_5,   g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_6,   g.rc_3.radio_min);
-
-	#if FRAME_CONFIG == TRI_FRAME
-	APM_RC.OutputCh(CH_TRI_YAW,   g.rc_4.radio_trim); // Yaw servo middle position
-	#endif
-
-	#if FRAME_CONFIG ==	OCTA_FRAME
-	APM_RC.OutputCh(MOT_7,   g.rc_3.radio_min);
-	APM_RC.OutputCh(MOT_8,   g.rc_3.radio_min);
-	#endif
-
+	motors.enable();
+	motors.output_min();
 }
 static void read_radio()
 {
@@ -158,7 +146,7 @@ static void throttle_failsafe(uint16_t pwm)
 			// Don't enter Failsafe if we are not armed
 			// home distance is in meters
 			// This is to prevent accidental RTL
-			if((motor_armed == true) && (home_distance > 1000)){
+			if(motors.armed() && (home_distance > 1000)){
 				SendDebug("MSG FS ON ");
 				SendDebugln(pwm, DEC);
 				set_failsafe(true);
diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde
index 8d804de75bcd327537a3f6645e39b05e6e736761..e7c6665bfbacbecad9099aa4965fea28844ab748 100644
--- a/ArduCopter/setup.pde
+++ b/ArduCopter/setup.pde
@@ -234,7 +234,7 @@ setup_motors(uint8_t argc, const Menu::arg *argv)
 	while(1){
 		delay(20);
 		read_radio();
-		output_motor_test();
+		motors.output_test();
 		if(Serial.available() > 0){
 			g.esc_calibrate.set_and_save(0);
 			return(0);
@@ -460,10 +460,10 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
 	int max_roll=0, max_pitch=0, min_collective=0, max_collective=0, min_tail=0, max_tail=0;
 
 	// initialise swash plate
-	heli_init_swash();
+	motors.init_swash();
 
 	// source swash plate movements directly from radio
-	g.heli_servo_manual = true;
+	motors.servo_manual = true;
 
 	// display initial settings
 	report_heli();
@@ -489,7 +489,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
 	    read_radio();
 
 		// allow swash plate to move
-		output_motors_armed();
+		motors.output_armed();
 
 		// record min/max
 		if( state == 1 ) {
@@ -529,8 +529,8 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
 				case 'c':
 				case 'C':
 				    if( g.rc_3.radio_out >= 900 && g.rc_3.radio_out <= 2100 ) {
-						g.heli_collective_mid = g.rc_3.radio_out;
-						Serial.printf_P(PSTR("Collective when blade pitch at zero: %d\n"),(int)g.heli_collective_mid);
+						motors.collective_mid = g.rc_3.radio_out;
+						Serial.printf_P(PSTR("Collective when blade pitch at zero: %d\n"),(int)motors.collective_mid);
 					}
 					break;
 				case 'd':
@@ -545,11 +545,11 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
 						Serial.printf_P(PSTR("Move coll, roll, pitch and tail to extremes, press 'm' when done\n"));
 
 						// reset servo ranges
-						g.heli_roll_max = g.heli_pitch_max = 4500;
-						g.heli_collective_min = 1000;
-						g.heli_collective_max = 2000;
-						g.heli_servo_4.radio_min = 1000;
-						g.heli_servo_4.radio_max = 2000;
+						motors.roll_max = motors.pitch_max = 4500;
+						motors.collective_min = 1000;
+						motors.collective_max = 2000;
+						motors._servo_4->radio_min = 1000;
+						motors._servo_4->radio_max = 2000;
 
 						// set sensible values in temp variables
 						max_roll = abs(g.rc_1.control_in);
@@ -563,15 +563,15 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
 						if( max_roll <= 1000 || max_pitch <= 1000 || (max_collective - min_collective < 200) || (max_tail - min_tail < 200) || min_tail < 1000 || max_tail > 2000 )
 						    Serial.printf_P(PSTR("Invalid min/max captured roll:%d,  pitch:%d,  collective min: %d max: %d,  tail min:%d max:%d\n"),max_roll,max_pitch,min_collective,max_collective,min_tail,max_tail);
 						else{
-						    g.heli_roll_max = max_roll;
-							g.heli_pitch_max = max_pitch;
-							g.heli_collective_min = min_collective;
-							g.heli_collective_max = max_collective;
-							g.heli_servo_4.radio_min = min_tail;
-							g.heli_servo_4.radio_max = max_tail;
+						    motors.roll_max = max_roll;
+							motors.pitch_max = max_pitch;
+							motors.collective_min = min_collective;
+							motors.collective_max = max_collective;
+							motors._servo_4->radio_min = min_tail;
+							motors._servo_4->radio_max = max_tail;
 
 							// reinitialise swash
-							heli_init_swash();
+							motors.init_swash();
 
 							// display settings
 							report_heli();
@@ -583,12 +583,12 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
 					temp = read_num_from_serial();
 					if( temp >= -360 && temp <= 360 ) {
 						if( active_servo == CH_1 )
-							g.heli_servo1_pos = temp;
+							motors.servo1_pos = temp;
 						if( active_servo == CH_2 )
-							g.heli_servo2_pos = temp;
+							motors.servo2_pos = temp;
 						if( active_servo == CH_3 )
-							g.heli_servo3_pos = temp;
-						heli_init_swash();
+							motors.servo3_pos = temp;
+						motors.init_swash();
 						Serial.printf_P(PSTR("Servo %d\t\tpos:%d\n"),active_servo+1, temp);
 					}
 					break;
@@ -603,7 +603,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
 					    temp -= 1500;
 					if( temp > -500 && temp < 500 ) {
 					    heli_get_servo(active_servo)->radio_trim = 1500 + temp;
-						heli_init_swash();
+						motors.init_swash();
 						Serial.printf_P(PSTR("Servo %d\t\ttrim:%d\n"),active_servo+1, 1500 + temp);
 					}
 					break;
@@ -618,12 +618,14 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
 					if( Serial.available() ) {
 					    value = Serial.read();
 						if( value == 'a' || value == 'A' ) {
-							g.heli_servo_averaging = HELI_SERVO_AVERAGING_ANALOG;
-							Serial.printf_P(PSTR("Analog Servo %dhz\n"),250 / HELI_SERVO_AVERAGING_ANALOG);
+							g.rc_speed.set_and_save(AP_MOTORS_HELI_SPEED_ANALOG_SERVOS);
+							//motors._speed_hz = AP_MOTORS_HELI_SPEED_ANALOG_SERVOS;  // need to force this update to take effect immediately
+							Serial.printf_P(PSTR("Analog Servo %dhz\n"),(int)g.rc_speed);
 						}
 						if( value == 'd' || value == 'D' ) {
-							g.heli_servo_averaging = HELI_SERVO_AVERAGING_DIGITAL;
-							Serial.printf_P(PSTR("Digital Servo 250hz\n"));
+							g.rc_speed.set_and_save(AP_MOTORS_HELI_SPEED_ANALOG_SERVOS);
+							//motors._speed_hz = AP_MOTORS_HELI_SPEED_ANALOG_SERVOS;  // need to force this update to take effect immediately
+							Serial.printf_P(PSTR("Digital Servo %dhz\n"),(int)g.rc_speed);
 						}
 					}
 					break;
@@ -641,22 +643,21 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
 	report_heli();
 
 	// save to eeprom
-	g.heli_servo_1.save_eeprom();
-	g.heli_servo_2.save_eeprom();
-	g.heli_servo_3.save_eeprom();
-	g.heli_servo_4.save_eeprom();
-	g.heli_servo1_pos.save();
-	g.heli_servo2_pos.save();
-	g.heli_servo3_pos.save();
-	g.heli_roll_max.save();
-	g.heli_pitch_max.save();
-	g.heli_collective_min.save();
-	g.heli_collective_max.save();
-	g.heli_collective_mid.save();
-	g.heli_servo_averaging.save();
+	motors._servo_1->save_eeprom();
+	motors._servo_2->save_eeprom();
+	motors._servo_3->save_eeprom();
+	motors._servo_4->save_eeprom();
+	motors.servo1_pos.save();
+	motors.servo2_pos.save();
+	motors.servo3_pos.save();
+	motors.roll_max.save();
+	motors.pitch_max.save();
+	motors.collective_min.save();
+	motors.collective_max.save();
+	motors.collective_mid.save();
 
 	// return swash plate movements to attitude controller
-	g.heli_servo_manual = false;
+	motors.servo_manual = false;
 
 	return(0);
 }
@@ -666,22 +667,22 @@ static int8_t
 setup_gyro(uint8_t argc, const Menu::arg *argv)
 {
 	if (!strcmp_P(argv[1].str, PSTR("on"))) {
-		g.heli_ext_gyro_enabled.set_and_save(true);
+		motors.ext_gyro_enabled.set_and_save(true);
 
 		// optionally capture the gain
 		if( argc >= 2 && argv[2].i >= 1000 && argv[2].i <= 2000 ) {
-		    g.heli_ext_gyro_gain = argv[2].i;
-			g.heli_ext_gyro_gain.save();
+		    motors.ext_gyro_gain = argv[2].i;
+			motors.ext_gyro_gain.save();
 		}
 
 	} else if (!strcmp_P(argv[1].str, PSTR("off"))) {
-		g.heli_ext_gyro_enabled.set_and_save(false);
+		motors.ext_gyro_enabled.set_and_save(false);
 
     // capture gain if user simply provides a number
 	} else if( argv[1].i >= 1000 && argv[1].i <= 2000 ) {
-	    g.heli_ext_gyro_enabled.set_and_save(true);
-		g.heli_ext_gyro_gain = argv[1].i;
-		g.heli_ext_gyro_gain.save();
+	    motors.ext_gyro_enabled.set_and_save(true);
+		motors.ext_gyro_gain = argv[1].i;
+		motors.ext_gyro_gain.save();
 
 	}else{
 		Serial.printf_P(PSTR("\nOp:[on, off] gain\n"));
@@ -928,29 +929,22 @@ void report_optflow()
 #if FRAME_CONFIG == HELI_FRAME
 static void report_heli()
 {
-    int servo_rate;
-
 	Serial.printf_P(PSTR("Heli\n"));
 	print_divider();
 
 	// main servo settings
 	Serial.printf_P(PSTR("Servo \tpos \tmin \tmax \trev\n"));
-	Serial.printf_P(PSTR("1:\t%d \t%d \t%d \t%d\n"),(int)g.heli_servo1_pos, (int)g.heli_servo_1.radio_min, (int)g.heli_servo_1.radio_max, (int)g.heli_servo_1.get_reverse());
-	Serial.printf_P(PSTR("2:\t%d \t%d \t%d \t%d\n"),(int)g.heli_servo2_pos, (int)g.heli_servo_2.radio_min, (int)g.heli_servo_2.radio_max, (int)g.heli_servo_2.get_reverse());
-	Serial.printf_P(PSTR("3:\t%d \t%d \t%d \t%d\n"),(int)g.heli_servo3_pos, (int)g.heli_servo_3.radio_min, (int)g.heli_servo_3.radio_max, (int)g.heli_servo_3.get_reverse());
-	Serial.printf_P(PSTR("tail:\t\t%d \t%d \t%d\n"), (int)g.heli_servo_4.radio_min, (int)g.heli_servo_4.radio_max, (int)g.heli_servo_4.get_reverse());
+	Serial.printf_P(PSTR("1:\t%d \t%d \t%d \t%d\n"),(int)motors.servo1_pos, (int)motors._servo_1->radio_min, (int)motors._servo_1->radio_max, (int)motors._servo_1->get_reverse());
+	Serial.printf_P(PSTR("2:\t%d \t%d \t%d \t%d\n"),(int)motors.servo2_pos, (int)motors._servo_2->radio_min, (int)motors._servo_2->radio_max, (int)motors._servo_2->get_reverse());
+	Serial.printf_P(PSTR("3:\t%d \t%d \t%d \t%d\n"),(int)motors.servo3_pos, (int)motors._servo_3->radio_min, (int)motors._servo_3->radio_max, (int)motors._servo_3->get_reverse());
+	Serial.printf_P(PSTR("tail:\t\t%d \t%d \t%d\n"), (int)motors._servo_4->radio_min, (int)motors._servo_4->radio_max, (int)motors._servo_4->get_reverse());
 
-	Serial.printf_P(PSTR("roll max: \t%d\n"), (int)g.heli_roll_max);
-	Serial.printf_P(PSTR("pitch max: \t%d\n"), (int)g.heli_pitch_max);
-	Serial.printf_P(PSTR("coll min:\t%d\t mid:%d\t max:%d\n"),(int)g.heli_collective_min, (int)g.heli_collective_mid, (int)g.heli_collective_max);
+	Serial.printf_P(PSTR("roll max: \t%d\n"), (int)motors.roll_max);
+	Serial.printf_P(PSTR("pitch max: \t%d\n"), (int)motors.pitch_max);
+	Serial.printf_P(PSTR("coll min:\t%d\t mid:%d\t max:%d\n"),(int)motors.collective_min, (int)motors.collective_mid, (int)motors.collective_max);
 
 	// calculate and print servo rate
-	if( g.heli_servo_averaging <= 1 ) {
-	    servo_rate = 250;
-	} else {
-	    servo_rate = 250 / g.heli_servo_averaging;
-	}
-	Serial.printf_P(PSTR("servo rate:\t%d hz\n"),servo_rate);
+	Serial.printf_P(PSTR("servo rate:\t%d hz\n"),(int)g.rc_speed);
 
 	print_blanks(2);
 }
@@ -961,9 +955,9 @@ static void report_gyro()
 	Serial.printf_P(PSTR("Gyro:\n"));
 	print_divider();
 
-	print_enabled( g.heli_ext_gyro_enabled );
-	if( g.heli_ext_gyro_enabled )
-	    Serial.printf_P(PSTR("gain: %d"),(int)g.heli_ext_gyro_gain);
+	print_enabled( motors.ext_gyro_enabled );
+	if( motors.ext_gyro_enabled )
+	    Serial.printf_P(PSTR("gain: %d"),(int)motors.ext_gyro_gain);
 
 	print_blanks(2);
 }
@@ -1052,13 +1046,13 @@ print_gyro_offsets(void)
 static RC_Channel *
 heli_get_servo(int servo_num){
 	if( servo_num == CH_1 )
-	    return &g.heli_servo_1;
+	    return motors._servo_1;
 	if( servo_num == CH_2 )
-	    return &g.heli_servo_2;
+	    return motors._servo_2;
 	if( servo_num == CH_3 )
-	    return &g.heli_servo_3;
+	    return motors._servo_3;
 	if( servo_num == CH_4 )
-	    return &g.heli_servo_4;
+	    return motors._servo_4;
 	return NULL;
 }
 
@@ -1116,23 +1110,13 @@ static void print_enabled(boolean b)
 static void
 init_esc()
 {
-	motors_output_enable();
+	motors.enable();
+	motors.armed(true);
 	while(1){
 		read_radio();
 		delay(100);
 		dancing_light();
-		APM_RC.OutputCh(MOT_1, g.rc_3.radio_in);
-		APM_RC.OutputCh(MOT_2, g.rc_3.radio_in);
-		APM_RC.OutputCh(MOT_3, g.rc_3.radio_in);
-		APM_RC.OutputCh(MOT_4, g.rc_3.radio_in);
-		APM_RC.OutputCh(MOT_5, g.rc_3.radio_in);
-		APM_RC.OutputCh(MOT_6, g.rc_3.radio_in);
-
-		#if FRAME_CONFIG ==	OCTA_FRAME
-		APM_RC.OutputCh(MOT_7,   g.rc_3.radio_in);
-		APM_RC.OutputCh(MOT_8,   g.rc_3.radio_in);
-		#endif
-
+		motors.throttle_pass_through();
 	}
 }
 
diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde
index 273384606d939df8312d85a2954c5281a3f1cc4a..b252083d8b9b5e1cc5ec4cd9bb96e0905e22c281 100644
--- a/ArduCopter/system.pde
+++ b/ArduCopter/system.pde
@@ -190,8 +190,8 @@ static void init_ardupilot()
 	#endif
 
     #if FRAME_CONFIG ==	HELI_FRAME
-		g.heli_servo_manual = false;
-		heli_init_swash();  // heli initialisation
+		motors.servo_manual = false;
+		motors.init_swash();  // heli initialisation
 	#endif
 
     RC_Channel::set_apm_rc(&APM_RC);
@@ -392,7 +392,7 @@ static void set_mode(byte mode)
 	control_mode 		= constrain(control_mode, 0, NUM_MODES - 1);
 
 	// used to stop fly_aways
-	motor_auto_armed = (g.rc_3.control_in > 0);
+	motors.auto_armed(g.rc_3.control_in > 0);
 
 	// clearing value used in interactive alt hold
 	manual_boost = 0;
@@ -507,7 +507,7 @@ static void set_mode(byte mode)
 		throttle_mode = THROTTLE_AUTO;
 		// does not wait for us to be in high throttle, since the
 		// Receiver will be outputting low throttle
-		motor_auto_armed = true;
+		motors.auto_armed(true);
 	}
 
 	// called to calculate gain for alt hold
diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde
index 714d102839b19c2619b500f1573432119bf878a9..635b9e58d38ba9908abe86633158a16dd548d498 100644
--- a/ArduCopter/test.pde
+++ b/ArduCopter/test.pde
@@ -316,8 +316,8 @@ test_radio(uint8_t argc, const Menu::arg *argv)
 	Serial.printf_P(PSTR("g.pi_stabilize_roll.kP: %4.4f\n"), g.pi_stabilize_roll.kP());
 	Serial.printf_P(PSTR("max_stabilize_dampener:%d\n\n "), max_stabilize_dampener);
 
-	motor_auto_armed 	= false;
-	motor_armed 		= true;
+	motors.auto_armed(false);
+	motors.armed(true);
 
 	while(1){
 		// 50 hz
@@ -766,11 +766,22 @@ test_tuning(uint8_t argc, const Menu::arg *argv)
 static int8_t
 test_battery(uint8_t argc, const Menu::arg *argv)
 {
-	#if defined( __AVR_ATmega1280__ )  // determines if optical flow code is included
+	#if defined( __AVR_ATmega1280__ )  // disable this test if we are using 1280
 		print_test_disabled();
 		return (0);
 	#else
+		Serial.printf_P(PSTR("\nCareful! Motors will spin! Press Enter to start.\n"));
+		Serial.flush();
+		while(!Serial.available()){
+			delay(100);
+		}
+		Serial.flush();
 		print_hit_enter();
+
+		// allow motors to spin
+		motors.enable();
+		motors.armed(true);
+
 		while(1){
 			delay(100);
 			read_radio();
@@ -786,15 +797,14 @@ test_battery(uint8_t argc, const Menu::arg *argv)
 									current_amps1,
 									current_total1);
 			}
-			APM_RC.OutputCh(MOT_1, g.rc_3.radio_in);
-			APM_RC.OutputCh(MOT_2, g.rc_3.radio_in);
-			APM_RC.OutputCh(MOT_3, g.rc_3.radio_in);
-			APM_RC.OutputCh(MOT_4, g.rc_3.radio_in);
+			motors.throttle_pass_through();
 
 			if(Serial.available() > 0){
+				motors.armed(false);
 				return (0);
 			}
 		}
+		motors.armed(false);
 		return (0);
 	#endif
 }
diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde
index 0b0efbf26120af712bb60476234c53c4072ffb7a..7740128199c7ad9c6b3ccf411a93daa80dc1aca8 100644
--- a/ArduPlane/ArduPlane.pde
+++ b/ArduPlane/ArduPlane.pde
@@ -1,6 +1,6 @@
 /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
 
-#define THISFIRMWARE "ArduPlane V2.32"
+#define THISFIRMWARE "ArduPlane V2.33"
 /*
 Authors:    Doug Weibel, Jose Julio, Jordi Munoz, Jason Short, Andrew Tridgell, Randy Mackay, Pat Hickey, John Arne Birkeland, Olivier Adler
 Thanks to:  Chris Anderson, Michael Oborne, Paul Mather, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi, Yury Smirnov, Sandro Benigno, Max Levine, Roberto Navoni, Lorenz Meier 
diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs
index f748e444623261dee2972d8f9859572d15cb67f3..448ceb7e107a3c53b234c44306b5a0c18ff78dd2 100644
--- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs
@@ -28,7 +28,6 @@
         /// </summary>
         private void InitializeComponent()
         {
-            System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Tracker));
             this.CMB_interface = new System.Windows.Forms.ComboBox();
             this.label1 = new System.Windows.Forms.Label();
             this.CMB_baudrate = new System.Windows.Forms.ComboBox();
@@ -317,7 +316,6 @@
             // 
             this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
             this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
-            this.ClientSize = new System.Drawing.Size(587, 212);
             this.Controls.Add(this.LBL_tilttrim);
             this.Controls.Add(this.LBL_pantrim);
             this.Controls.Add(this.label12);
@@ -344,9 +342,8 @@
             this.Controls.Add(this.CMB_serialport);
             this.Controls.Add(this.label1);
             this.Controls.Add(this.CMB_interface);
-            this.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
             this.Name = "Tracker";
-            this.Text = "Tracker";
+            this.Size = new System.Drawing.Size(587, 212);
             this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.Tracker_FormClosing);
             ((System.ComponentModel.ISupportInitialize)(this.TRK_pantrim)).EndInit();
             ((System.ComponentModel.ISupportInitialize)(this.TRK_tilttrim)).EndInit();
diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs
index 53bad8d3bba2e0fab36f12732d6c3515c49b8118..589f67111d03ae31e9b530065797d48f0e820397 100644
--- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs
+++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs
@@ -6,10 +6,11 @@ using System.Drawing;
 using System.Linq;
 using System.Text;
 using System.Windows.Forms;
+using ArdupilotMega.Controls.BackstageView;
 
 namespace ArdupilotMega.Antenna
 {
-    public partial class Tracker : Form
+    public partial class Tracker : BackStageViewContentPanel
     {
         System.Threading.Thread t12;
         static bool threadrun = false;
diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx
index 222a74addff376f7a18256f55e7d4028cc9a5826..7080a7d118e8cd7ec668e9bb0d8e90767e0c7a3c 100644
--- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx
+++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx
@@ -117,81 +117,4 @@
   <resheader name="writer">
     <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
   </resheader>
-  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
-  <data name="$this.Icon" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
-    <value>
-        AAABAAEAICAAAAEAIACoEAAAFgAAACgAAAAgAAAAQAAAAAEAIAAAAAAAABAAABILAAASCwAAAAAAAAAA
-        AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADOxkjAtnoOAKpJ4vyiK
-        c+8nh3D/J4Zv/yeHcP8oi3PvKpJ4vy6fg4AzsZIwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
-        AAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADjGo2AyspPfLZ+D/yiQ
-        d/8hlXj/G6F9/xeqg/8XqYL/GKqD/xuhfv8ilnn/KZB3/y2fhP8yspPfN8ajYAAAAAAAAAAAAAAAAAAA
-        AAAAAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADvRrDA1vpzfL6uN/yel
-        hP8XvJD/DMyY/wfQl/8FzJP/A8qS/wPJkf8EypL/BsyU/wnRmP8PzZn/Gb2R/yemhP8tqoz/Mb2a3zbQ
-        qkAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAA4y6ZgMbWV/yin
-        iP8WwZP/Btqf/wDPlf8AyI7/A8aP/yfNnv9T2LP/UNax/03XsP8506b/G8ya/wHKkf8F0Zf/CNuf/xLB
-        kv8fpYT/J7KQ/y7IomAAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAANcajny+w
-        kf8hqoj/CNSd/wDRlf8Axor/Hcyd/3Lhwf+p7Nj/o+vV/57m0/+X5dD/k+TN/4/jzf+K5Mz/fuHH/0PW
-        rf8HzJT/ANCT/wDRlv8OpX//HayI/yrFn58AAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAADDC
-        nmAtro7/H62J/wPWmv8Ay47/AMaO/3XhxP+e6tT/mObP/5Pjy/+Q4sr/jODJ/4ffx/+C3MT/f9vC/3nb
-        wf9y2r7/adq7/2DauP8ZzZv/Fdae/8T/9/9WxKj/HKuI/y7IomAAAAAAAAAAAAAAAAD///8AAAAAAAAA
-        AAAiuZMwKKyM/x6ohf8C1Zr/AMmL/wHGjv+49OL///////////9+3ML/f9zD/4Dcwv9+28L/e9rA/3bZ
-        vv9w1rr/Z9S4/17Rs/9Qz63/Qcyn/3LewP////////////n///8MpH7/JbKP/zXQqUAAAAAAAAAAAP//
-        /wAAAAAAAAAAABymhN8dnn//BNGa/wDKjP8AxY3/sfHf/////////////////2nXt/9w1rv/c9e8/3TX
-        vP9x17z/a9W5/2TTtf9Y0K//SMyp/zXFoP9i07X/////////////////f/LR/wDQlf8epYT/Mb2a3wAA
-        AAAAAAAA////AAAAAAADlnJgFZR1/wq4iv8AzpH/AMCD/4rmzf//////////////////////WdGv/2PU
-        tf9p1rf/atS4/2nUtv9i0rT/Vc+u/0fKpv8zxZz/Ws+w//////////////////////8GyJL/ANCS/xLB
-        kv8tq4z/OMajYAAAAAD///8AAAAAAACHZt8NkW//ANKV/wDChP9i27r//////////////////////9Dx
-        6P9MzKn/Vc+v/17Rsv9g0rP/XNCx/1XNrv9Fyaf/McSd/1fPr///////////////////////QM2m/ynK
-        oP8JzJX/C9yh/ymmhf80spPfAAAAAP///wAAcUwwAHtc/wCrfP8AyIv/AMKK////////////////////
-        /////////////5Dgyv9Gyqb/TMyq/07Nq/9MzKn/Qcmj/y/Fnf9Wzq3//////////////////////57k
-        0v8av5T/Lceg/yzOo/8M05v/Hr6T/zCghf80spIw////AABoRYAAclT/AL2H/wDBhf9R1rL/////////
-        ////////4vfw//////////////////H8+P9KzKn/Ocah/zTFnv8qwpj/Us2t////////////////////
-        ////////DLqM/yDBlv8wxp//OM6m/xPPm/8Xz53/LZF5/y+fg4////8AAGNAvwB7Wf8Aw4j/ALyC/4bj
-        yP+g5tL/g93E/2HSsv9Pzqz/Us6s//////////////////////9Yzq//Gr2S/0jLp///////////////
-        /////////////yrDm/8SvI//JMGY/zDHn/81zKT/Is2e/xTUnf8nl3v/LJJ5v////wAAXz3vAIlg/wDA
-        hf8AuoD/quzZ/5Hjyv9628D/ada2/1jRsP9Jy6f/a9a4//////////////////////+Y4s7/////////
-        //////////////////+c4tD/AbaH/xW8kf8jwZj/LcWd/y/Jn/8kzJ3/E9Ca/yGjgf8ri3Tv////AABd
-        PP8Ak2b/AL6D/w/Ekv+m6tf/j+HJ/3vawP9p1rf/W9Gx/0rNqf85yJ//Nsaf////////////////////
-        /////////////////////////////wCwe/8AtoT/ELqP/xu+k/8jwZj/KMeb/yHKm/8QzZf/HqyG/ymI
-        cf////8AAF07/wCSZP8AvYL/GMWU/6Dn1P+K38f/ddi+/27Wuf+E3MX/leHN/6fm1f+l5tX/neLQ////
-        ////////////////////////////////////////j9/J/27Vuv9Tzq7/JsKY/xa/kv8aw5T/FcaW/wvL
-        lf8aqoT/J4dw/////wAAXTv/AJFk/wC9gP8GwY3/mObQ/5rkz/+26dv/y/Hl/8Dt3/+06tz/pebV/5bg
-        zP+g5NL//////////////v///f7+//7+/v//////7fn2////////////tOnb/6Ll0v+v6Nj/jeDI/zXK
-        o/8IxJD/BMqS/xaqgv8lh2//////AABeO+8AgVf/AL1//wDBif/R9uv/1PPq/8Tv5P+36t3/rujY/6Lk
-        0v+U4cv/jt7J//j8+///////+/38//f8+//2+/r/+Pz7//3+/v/m9/P/9Pv6//D6+P9/28L/jd7J/5jj
-        z/+h5dL/qOvX/4Hmyf8f1J//E596/yOJcO////8AAGA8vwB3U/8p06P/hufM/8Ty5f/D7+T/s+vb/6bm
-        1P+c4c//j9/K/4vcyP/t+fb///7///j8/P/0+/r/8vr5//P7+f/1+/r/+/39///////i9fL/ZNO1/3HW
-        vP992sH/htzG/4vhyv+S5dD/mO7W/6X74v80noT/Io90v////wAAZkCAAHla/33ny/945cb/nunV/7Xr
-        3v+l5tT/luDN/4ndxv992cL/1vLq//v9/P/1+/n/8vv4//L69//z+/j/9Pv5/7Xo2//x+vn/////////
-        //+y59n/aNS3/3LWvP932r//fNzD/4Ljyf+J7ND/l/bd/yORdf8knH6A////AABuRzAAdlT/Xc6x/23o
-        xv9s4MH/qurZ/5jiz/+I3cb/edjA/8ju5f/3/Pv/8vv4//H6+P/y+/j/6/f0/7np3v/7/fz//v7+/6fk
-        1f+56tz///////////9h0bT/aNW4/23Wu/9v3L//dOLG/37w0f9m1rn/Hpt8/ymujTD///8AAAAAAACD
-        X98po4X/Z+7K/1vgvP+A4sf/jOHK/3rZwv+r59f/9Pv6/+/69//v+vf/8vr4/9fy6/9n0rf/VM6t/6Di
-        0v/N7+f/adO4/1PMrf9t1Lr/i9zI/1/Rs/9h0rX/ZNe4/2bbvf9s5sb/ePfV/z2ylf8lrozfAAAAAP//
-        /wAAAAAAAJNsYAWQbf9U1rP/Vee//0rYsf993sb/pebV//P7+v/s+Pb/6/f1/+749v+s5tj/Vc2u/1jP
-        r/9ZzrD/btW5/1bOr/9Wza//Vs6v/1fOr/9Z0LD/WdCy/1vTtP9d1rX/Xt+8/2btyP9k4L//IaaF/y7D
-        nmAAAAAA////AAAAAAAAAAAAD6J9zyCjgv9S68L/P9+0/2Pevv/5////7/v6/+v59//j9/L/gtvF/1PN
-        r/9Wz7D/Wc+x/1nQsf9Zz7H/WM6w/1fPsP9UzrD/VM+w/1TPrv9U0a//U9Oy/1Tatv9Z5sD/Y/LL/zSx
-        lP8qupbPAAAAAAAAAAD///8AAAAAAAAAAAAYto4wGaeE/y23lP8+5rn/6/////j////w//3/ve/i/2bV
-        uP9Tzq7/Vc+v/1jPsP9Z0LL/WM+w/1fOsf9Wz7D/Us2w/1HOrf9Qzq3/T9Cu/0zSr/9M2LP/TeC5/1bt
-        xP9HxaX/KLKQ/zTPqDAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAkvpdgG6iF/y++m//e/////P///3rl
-        yf9G0K3/VdKy/1bPsf9Wz7H/Vs6w/1bPsP9Sza//Ucyu/0/Nrf9NzKz/S82s/0fOrP9G0a7/QdWv/0Le
-        tP9I6L7/Q8Ok/yitjP8yyKJgAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAmwJlgG6iF/yK3
-        kP8k3q7/H9el/x7Pn/8tzKT/Q9Cs/1HQsP9Q0K7/TM6u/0nMrf9Hzaz/RMyp/0LNqf8+zqn/ONGo/zTV
-        qf833rD/O+S4/zvCof8orIv/MMSfYAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAA
-        AAAkvpdgG6iE/xukgv8gy53/HNql/xzRn/8czJz/HcmZ/yXJnP8qyp7/Lcqg/yzLn/8nypz/JMqc/yTO
-        n/8l1KT/KN2r/y3Tpv8nq4n/JaqJ/yzAm2AAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAA
-        AAAAAAAAAAAAAAAAAAAato8wFKN/zxCScv8RnHn/DbqM/wjIlP8GyZT/BsaS/wbFkf8GxZH/B8WR/wfH
-        k/8IypX/DMmV/xG3jP8WoX3/Fph2/xqkgs8ft5EwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA////AAAA
-        AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJVvYACGZM8Aelr/AHlZ/wCFX/8AiWL/AJlr/wCb
-        bP8AlGf/AI5k/wB/W/8AeFj/AHtb/wCHZd8ClXBgAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
-        AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAABwSzAAaESAAGI/vwBf
-        Pd8AXTz/AF08/wBdPP8AXz3fAGJAvwBoRIAAcUswAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
-        AAAAAAAAAAAAAP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
-        /wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
-        /wD///8A////AP///wD///8A/+AD//+AAP/+AAA//AAAH/gAAA/wAAAH4AAAA+AAAAPAAAABwAAAAYAA
-        AACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAwAAAAcAAAAHgAAAD4AAAA/AA
-        AAf4AAAP/AAAH/4AAD//gAD//+AD//////8=
-</value>
-  </data>
 </root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
index bd24ec452944fbf9815eac0ce2cab366c7885017..a465ce36630a92cc1264db25aa277ea2b26e94af 100644
--- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
+++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
@@ -45,7 +45,7 @@
     <DefineConstants>TRACE;DEBUG;MAVLINK10cra</DefineConstants>
     <ErrorReport>prompt</ErrorReport>
     <WarningLevel>4</WarningLevel>
-    <AllowUnsafeBlocks>false</AllowUnsafeBlocks>
+    <AllowUnsafeBlocks>true</AllowUnsafeBlocks>
     <DocumentationFile>
     </DocumentationFile>
     <CheckForOverflowUnderflow>false</CheckForOverflowUnderflow>
@@ -61,7 +61,7 @@
     <DefineConstants>TRACE;DEBUG;MAVLINK10cra</DefineConstants>
     <ErrorReport>prompt</ErrorReport>
     <WarningLevel>4</WarningLevel>
-    <AllowUnsafeBlocks>false</AllowUnsafeBlocks>
+    <AllowUnsafeBlocks>true</AllowUnsafeBlocks>
     <DocumentationFile>
     </DocumentationFile>
     <CheckForOverflowUnderflow>false</CheckForOverflowUnderflow>
@@ -80,7 +80,7 @@
     <ManifestKeyFile>ArdupilotMega_TemporaryKey.pfx</ManifestKeyFile>
   </PropertyGroup>
   <PropertyGroup>
-    <GenerateManifests>true</GenerateManifests>
+    <GenerateManifests>false</GenerateManifests>
   </PropertyGroup>
   <PropertyGroup>
     <SignManifests>false</SignManifests>
@@ -148,11 +148,11 @@
     </Reference>
     <Reference Include="Microsoft.DirectX, Version=1.0.2902.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35">
       <SpecificVersion>False</SpecificVersion>
-      <Private>False</Private>
+      <Private>True</Private>
     </Reference>
     <Reference Include="Microsoft.DirectX.DirectInput, Version=1.0.2902.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35">
       <SpecificVersion>False</SpecificVersion>
-      <Private>False</Private>
+      <Private>True</Private>
     </Reference>
     <Reference Include="Microsoft.Dynamic">
     </Reference>
@@ -217,7 +217,7 @@
     <Compile Include="Antenna\ITrackerOutput.cs" />
     <Compile Include="Antenna\Maestro.cs" />
     <Compile Include="Antenna\Tracker.cs">
-      <SubType>Form</SubType>
+      <SubType>UserControl</SubType>
     </Compile>
     <Compile Include="Antenna\Tracker.Designer.cs">
       <DependentUpon>Tracker.cs</DependentUpon>
@@ -232,6 +232,9 @@
     <Compile Include="Controls\BackstageView\BackstageViewButton.cs">
       <SubType>Component</SubType>
     </Compile>
+    <Compile Include="Controls\BackstageView\BackStageViewContentPanel.cs">
+      <SubType>UserControl</SubType>
+    </Compile>
     <Compile Include="Controls\BackstageView\BackStageViewMenuPanel.cs">
       <SubType>Component</SubType>
     </Compile>
@@ -297,7 +300,7 @@
       <DependentUpon>ConfigTradHeli.cs</DependentUpon>
     </Compile>
     <Compile Include="GCSViews\ConfigurationView\Configuration.cs">
-      <SubType>UserControl</SubType>
+      <SubType>Form</SubType>
     </Compile>
     <Compile Include="GCSViews\ConfigurationView\Configuration.Designer.cs">
       <DependentUpon>Configuration.cs</DependentUpon>
@@ -308,10 +311,17 @@
     <Compile Include="GCSViews\ConfigurationView\ConfigRawParams.Designer.cs">
       <DependentUpon>ConfigRawParams.cs</DependentUpon>
     </Compile>
+    <Compile Include="GCSViews\ConfigurationView\Setup.cs">
+      <SubType>Form</SubType>
+    </Compile>
+    <Compile Include="GCSViews\ConfigurationView\Setup.Designer.cs">
+      <DependentUpon>Setup.cs</DependentUpon>
+    </Compile>
     <Compile Include="MagCalib.cs" />
+    <Compile Include="Mavlink\MavlinkOther.cs" />
     <Compile Include="PIDTunning.cs" />
     <Compile Include="Radio\3DRradio.cs">
-      <SubType>Form</SubType>
+      <SubType>UserControl</SubType>
     </Compile>
     <Compile Include="Radio\3DRradio.Designer.cs">
       <DependentUpon>3DRradio.cs</DependentUpon>
@@ -503,12 +513,6 @@
     <Compile Include="SerialOutput.Designer.cs">
       <DependentUpon>SerialOutput.cs</DependentUpon>
     </Compile>
-    <Compile Include="Setup\Setup.cs">
-      <SubType>Form</SubType>
-    </Compile>
-    <Compile Include="Setup\Setup.Designer.cs">
-      <DependentUpon>Setup.cs</DependentUpon>
-    </Compile>
     <Compile Include="Speech.cs" />
     <Compile Include="Splash.cs">
       <SubType>Form</SubType>
@@ -536,39 +540,150 @@
     <EmbeddedResource Include="Controls\ProgressReporterDialogue.resx">
       <DependentUpon>ProgressReporterDialogue.cs</DependentUpon>
     </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigAccelerometerCalibration.es-ES.resx">
+      <DependentUpon>ConfigAccelerometerCalibration.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigAccelerometerCalibration.fr.resx">
+      <DependentUpon>ConfigAccelerometerCalibration.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigAccelerometerCalibration.it-IT.resx">
+      <DependentUpon>ConfigAccelerometerCalibration.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigAccelerometerCalibration.pl.resx">
+      <DependentUpon>ConfigAccelerometerCalibration.cs</DependentUpon>
+    </EmbeddedResource>
     <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigAccelerometerCalibration.resx">
       <DependentUpon>ConfigAccelerometerCalibration.cs</DependentUpon>
     </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigAccelerometerCalibration.zh-Hans.resx">
+      <DependentUpon>ConfigAccelerometerCalibration.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigAccelerometerCalibration.zh-TW.resx">
+      <DependentUpon>ConfigAccelerometerCalibration.cs</DependentUpon>
+    </EmbeddedResource>
     <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigArducopter.resx">
       <DependentUpon>ConfigArducopter.cs</DependentUpon>
     </EmbeddedResource>
     <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigArduplane.resx">
       <DependentUpon>ConfigArduplane.cs</DependentUpon>
     </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigBatteryMonitoring.es-ES.resx">
+      <DependentUpon>ConfigBatteryMonitoring.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigBatteryMonitoring.fr.resx">
+      <DependentUpon>ConfigBatteryMonitoring.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigBatteryMonitoring.it-IT.resx">
+      <DependentUpon>ConfigBatteryMonitoring.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigBatteryMonitoring.pl.resx">
+      <DependentUpon>ConfigBatteryMonitoring.cs</DependentUpon>
+    </EmbeddedResource>
     <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigBatteryMonitoring.resx">
       <DependentUpon>ConfigBatteryMonitoring.cs</DependentUpon>
     </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigBatteryMonitoring.zh-Hans.resx">
+      <DependentUpon>ConfigBatteryMonitoring.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigBatteryMonitoring.zh-TW.resx">
+      <DependentUpon>ConfigBatteryMonitoring.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigFlightModes.es-ES.resx">
+      <DependentUpon>ConfigFlightModes.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigFlightModes.fr.resx">
+      <DependentUpon>ConfigFlightModes.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigFlightModes.it-IT.resx">
+      <DependentUpon>ConfigFlightModes.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigFlightModes.pl.resx">
+      <DependentUpon>ConfigFlightModes.cs</DependentUpon>
+    </EmbeddedResource>
     <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigFlightModes.resx">
       <DependentUpon>ConfigFlightModes.cs</DependentUpon>
     </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigFlightModes.zh-Hans.resx">
+      <DependentUpon>ConfigFlightModes.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigFlightModes.zh-TW.resx">
+      <DependentUpon>ConfigFlightModes.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigHardwareOptions.es-ES.resx">
+      <DependentUpon>ConfigHardwareOptions.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigHardwareOptions.fr.resx">
+      <DependentUpon>ConfigHardwareOptions.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigHardwareOptions.it-IT.resx">
+      <DependentUpon>ConfigHardwareOptions.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigHardwareOptions.pl.resx">
+      <DependentUpon>ConfigHardwareOptions.cs</DependentUpon>
+    </EmbeddedResource>
     <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigHardwareOptions.resx">
       <DependentUpon>ConfigHardwareOptions.cs</DependentUpon>
     </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigHardwareOptions.zh-Hans.resx">
+      <DependentUpon>ConfigHardwareOptions.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigHardwareOptions.zh-TW.resx">
+      <DependentUpon>ConfigHardwareOptions.cs</DependentUpon>
+    </EmbeddedResource>
     <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigPlanner.resx">
       <DependentUpon>ConfigPlanner.cs</DependentUpon>
     </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigRadioInput.es-ES.resx">
+      <DependentUpon>ConfigRadioInput.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigRadioInput.fr.resx">
+      <DependentUpon>ConfigRadioInput.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigRadioInput.it-IT.resx">
+      <DependentUpon>ConfigRadioInput.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigRadioInput.pl.resx">
+      <DependentUpon>ConfigRadioInput.cs</DependentUpon>
+    </EmbeddedResource>
     <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigRadioInput.resx">
       <DependentUpon>ConfigRadioInput.cs</DependentUpon>
     </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigRadioInput.zh-Hans.resx">
+      <DependentUpon>ConfigRadioInput.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigRadioInput.zh-TW.resx">
+      <DependentUpon>ConfigRadioInput.cs</DependentUpon>
+    </EmbeddedResource>
     <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigRawParams.resx">
       <DependentUpon>ConfigRawParams.cs</DependentUpon>
     </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigTradHeli.es-ES.resx">
+      <DependentUpon>ConfigTradHeli.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigTradHeli.fr.resx">
+      <DependentUpon>ConfigTradHeli.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigTradHeli.it-IT.resx">
+      <DependentUpon>ConfigTradHeli.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigTradHeli.pl.resx">
+      <DependentUpon>ConfigTradHeli.cs</DependentUpon>
+    </EmbeddedResource>
     <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigTradHeli.resx">
       <DependentUpon>ConfigTradHeli.cs</DependentUpon>
     </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigTradHeli.zh-Hans.resx">
+      <DependentUpon>ConfigTradHeli.cs</DependentUpon>
+    </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\ConfigTradHeli.zh-TW.resx">
+      <DependentUpon>ConfigTradHeli.cs</DependentUpon>
+    </EmbeddedResource>
     <EmbeddedResource Include="GCSViews\ConfigurationView\Configuration.resx">
       <DependentUpon>Configuration.cs</DependentUpon>
     </EmbeddedResource>
+    <EmbeddedResource Include="GCSViews\ConfigurationView\Setup.resx">
+      <DependentUpon>Setup.cs</DependentUpon>
+    </EmbeddedResource>
     <EmbeddedResource Include="Radio\3DRradio.resx">
       <DependentUpon>3DRradio.cs</DependentUpon>
     </EmbeddedResource>
@@ -899,28 +1014,6 @@
     <EmbeddedResource Include="SerialOutput.resx">
       <DependentUpon>SerialOutput.cs</DependentUpon>
     </EmbeddedResource>
-    <EmbeddedResource Include="Setup\Setup.es-ES.resx">
-      <DependentUpon>Setup.cs</DependentUpon>
-    </EmbeddedResource>
-    <EmbeddedResource Include="Setup\Setup.fr.resx">
-      <DependentUpon>Setup.cs</DependentUpon>
-    </EmbeddedResource>
-    <EmbeddedResource Include="Setup\Setup.it-IT.resx">
-      <DependentUpon>Setup.cs</DependentUpon>
-    </EmbeddedResource>
-    <EmbeddedResource Include="Setup\Setup.pl.resx">
-      <DependentUpon>Setup.cs</DependentUpon>
-    </EmbeddedResource>
-    <EmbeddedResource Include="Setup\Setup.resx">
-      <DependentUpon>Setup.cs</DependentUpon>
-      <SubType>Designer</SubType>
-    </EmbeddedResource>
-    <EmbeddedResource Include="Setup\Setup.zh-Hans.resx">
-      <DependentUpon>Setup.cs</DependentUpon>
-    </EmbeddedResource>
-    <EmbeddedResource Include="Setup\Setup.zh-TW.resx">
-      <DependentUpon>Setup.cs</DependentUpon>
-    </EmbeddedResource>
     <EmbeddedResource Include="Splash.resx">
       <DependentUpon>Splash.cs</DependentUpon>
     </EmbeddedResource>
@@ -939,6 +1032,8 @@
     </None>
     <None Include="MAC\Info.plist" />
     <None Include="MAC\run.sh" />
+    <None Include="Msi\installer.bat" />
+    <None Include="Msi\installer.wxs" />
     <None Include="mykey.snk" />
     <None Include="Properties\app.manifest" />
     <None Include="Properties\DataSources\CurrentState.datasource" />
@@ -952,6 +1047,9 @@
   </ItemGroup>
   <ItemGroup>
     <Content Include="apm2.ico" />
+    <Content Include="Driver\Arduino MEGA 2560.inf">
+      <CopyToOutputDirectory>Always</CopyToOutputDirectory>
+    </Content>
     <Content Include="hud.html">
       <CopyToOutputDirectory>Always</CopyToOutputDirectory>
       <SubType>Designer</SubType>
@@ -1049,7 +1147,7 @@
   <ItemGroup />
   <Import Project="$(MSBuildToolsPath)\Microsoft.CSharp.targets" />
   <PropertyGroup>
-    <PostBuildEvent>rem macos.bat</PostBuildEvent>
+    <PostBuildEvent>"$(TargetDir)version.exe" "$(TargetPath)" &gt; "$(TargetDir)version.txt"</PostBuildEvent>
   </PropertyGroup>
   <PropertyGroup>
     <PreBuildEvent>
diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.sln b/Tools/ArdupilotMegaPlanner/ArdupilotMega.sln
index 8c86aa7b2d4c7b50e14ae3351dcada65bad60df1..54de868e9ec1ea3a0babdcb51a1bc5253e63f9d2 100644
--- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.sln
+++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.sln
@@ -2,9 +2,14 @@
 Microsoft Visual Studio Solution File, Format Version 11.00
 # Visual C# Express 2010
 Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "ArdupilotMega", "ArdupilotMega.csproj", "{A2E22272-95FE-47B6-B050-9AE7E2055BF5}"
+	ProjectSection(ProjectDependencies) = postProject
+		{76374F95-C343-4ACC-B86F-7ECFDD668F46} = {76374F95-C343-4ACC-B86F-7ECFDD668F46}
+	EndProjectSection
 EndProject
 Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "Updater", "Updater\Updater.csproj", "{E64A1A41-A5B0-458E-8284-BB63705354DA}"
 EndProject
+Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "wix", "wix\wix.csproj", "{76374F95-C343-4ACC-B86F-7ECFDD668F46}"
+EndProject
 Global
 	GlobalSection(SolutionConfigurationPlatforms) = preSolution
 		Debug|Any CPU = Debug|Any CPU
@@ -41,6 +46,18 @@ Global
 		{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|Win32.ActiveCfg = Release|x86
 		{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|x86.ActiveCfg = Release|x86
 		{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|x86.Build.0 = Release|x86
+		{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Debug|Any CPU.ActiveCfg = Debug|x86
+		{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Debug|Mixed Platforms.ActiveCfg = Debug|x86
+		{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Debug|Mixed Platforms.Build.0 = Debug|x86
+		{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Debug|Win32.ActiveCfg = Debug|x86
+		{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Debug|x86.ActiveCfg = Debug|x86
+		{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Debug|x86.Build.0 = Debug|x86
+		{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Release|Any CPU.ActiveCfg = Release|x86
+		{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Release|Mixed Platforms.ActiveCfg = Release|x86
+		{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Release|Mixed Platforms.Build.0 = Release|x86
+		{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Release|Win32.ActiveCfg = Release|x86
+		{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Release|x86.ActiveCfg = Release|x86
+		{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Release|x86.Build.0 = Release|x86
 	EndGlobalSection
 	GlobalSection(SolutionProperties) = preSolution
 		HideSolutionNode = FALSE
diff --git a/Tools/ArdupilotMegaPlanner/CodeGen.cs b/Tools/ArdupilotMegaPlanner/CodeGen.cs
index f3faeaca2aa1d053dea83a0e9deaccc5ca2775ad..cdde571ed01350341650c53c423b7364fd3f4825 100644
--- a/Tools/ArdupilotMegaPlanner/CodeGen.cs
+++ b/Tools/ArdupilotMegaPlanner/CodeGen.cs
@@ -16,9 +16,9 @@ namespace ArdupilotMega
 {
     static class CodeGen
     {
-        public static string runCode(string code)
+        public static object runCode(string code)
         {
-            string answer = "";
+            object answer = null;
 
             GetMathMemberNames();
 
@@ -49,13 +49,12 @@ namespace ArdupilotMega
             return answer;
         }
 
-        static ICodeCompiler CreateCompiler()
+        static CodeDomProvider CreateCompiler()
         {
             //Create an instance of the C# compiler   
-            CodeDomProvider codeProvider = null;
-            codeProvider = new CSharpCodeProvider();
-            ICodeCompiler compiler = codeProvider.CreateCompiler();
-            return compiler;
+            CodeDomProvider codeProvider = CodeDomProvider.CreateProvider("CSharp");
+            //ICodeCompiler compiler = codeProvider.CreateCompiler();
+            return codeProvider;
         }
 
         /// <summary>
@@ -88,7 +87,7 @@ namespace ArdupilotMega
         /// <param name="parms"></param>
         /// <param name="source"></param>
         /// <returns></returns>
-        static private CompilerResults CompileCode(ICodeCompiler compiler, CompilerParameters parms, string source)
+        static private CompilerResults CompileCode(CodeDomProvider compiler, CompilerParameters parms, string source)
         {
             //actually compile the code
             CompilerResults results = compiler.CompileAssemblyFromSource(
@@ -144,7 +143,7 @@ namespace ArdupilotMega
         static private CompilerResults CompileAssembly()
         {
             // create a compiler
-            ICodeCompiler compiler = CreateCompiler();
+            CodeDomProvider compiler = CreateCompiler();
             // get all the compiler parameters
             CompilerParameters parms = CreateCompilerParameters();
             // compile the code into an assembly
@@ -306,7 +305,7 @@ namespace ArdupilotMega
             classDeclaration.IsClass = true;
             classDeclaration.Name = "Calculator";
             classDeclaration.Attributes = MemberAttributes.Public;
-            classDeclaration.Members.Add(FieldVariable("answer", typeof(string), MemberAttributes.Private));
+            classDeclaration.Members.Add(FieldVariable("answer", typeof(object), MemberAttributes.Private));
 
             //default constructor
             CodeConstructor defaultConstructor = new CodeConstructor();
@@ -316,16 +315,16 @@ namespace ArdupilotMega
             classDeclaration.Members.Add(defaultConstructor);
 
             //property
-            classDeclaration.Members.Add(MakeProperty("Answer", "answer", typeof(string)));
+            classDeclaration.Members.Add(MakeProperty("Answer", "answer", typeof(object)));
 
             //Our Calculate Method
             CodeMemberMethod myMethod = new CodeMemberMethod();
             myMethod.Name = "Calculate";
-            myMethod.ReturnType = new CodeTypeReference(typeof(string));
+            myMethod.ReturnType = new CodeTypeReference(typeof(object));
             myMethod.Comments.Add(new CodeCommentStatement("Calculate an expression", true));
             myMethod.Attributes = MemberAttributes.Public;
             myMethod.Statements.Add(new CodeAssignStatement(new CodeSnippetExpression("Object obj"), new CodeSnippetExpression(expression)));
-            myMethod.Statements.Add(new CodeAssignStatement(new CodeSnippetExpression("Answer"), new CodeSnippetExpression("obj.ToString()")));
+            //myMethod.Statements.Add(new CodeAssignStatement(new CodeSnippetExpression("Answer"), new CodeSnippetExpression("obj.ToString()")));
             myMethod.Statements.Add(
                            new CodeMethodReturnStatement(new CodeFieldReferenceExpression(new CodeThisReferenceExpression(), "Answer")));
             classDeclaration.Members.Add(myMethod);
diff --git a/Tools/ArdupilotMegaPlanner/Common.cs b/Tools/ArdupilotMegaPlanner/Common.cs
index 826ae2117d09289302abea1253ebf4665c1c7fe5..4a596aeca5e2217e20f4101fc14ba56491263923 100644
--- a/Tools/ArdupilotMegaPlanner/Common.cs
+++ b/Tools/ArdupilotMegaPlanner/Common.cs
@@ -386,7 +386,8 @@ namespace ArdupilotMega
             CH6_ACRO_KP = 25,
             CH6_YAW_RATE_KD = 26,
             CH6_LOITER_KI = 27,
-            CH6_LOITER_RATE_KI = 28
+            CH6_LOITER_RATE_KI = 28,
+            CH6_STABILIZE_KD = 29
         }
 
 
@@ -428,9 +429,9 @@ namespace ArdupilotMega
        
 		#if MAVLINK10
 		
-        public static bool translateMode(string modein, ref MAVLink.__mavlink_set_mode_t mode)
+        public static bool translateMode(string modein, ref MAVLink.mavlink_set_mode_t mode)
         {
-            //MAVLink.__mavlink_set_mode_t mode = new MAVLink.__mavlink_set_mode_t();
+            //MAVLink.mavlink_set_mode_t mode = new MAVLink.mavlink_set_mode_t();
             mode.target_system = MainV2.comPort.sysid;
 
             try
@@ -447,7 +448,7 @@ namespace ArdupilotMega
                         case (int)Common.apmmodes.LOITER:
                         case (int)Common.apmmodes.FLY_BY_WIRE_A:
                         case (int)Common.apmmodes.FLY_BY_WIRE_B:
-                            mode.base_mode = (byte)MAVLink.MAV_MODE_FLAG.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
+                            mode.base_mode = (byte)MAVLink.MAV_MODE_FLAG.CUSTOM_MODE_ENABLED;
                             mode.custom_mode = (uint)(int)Enum.Parse(Common.getModes(), modein);
                             break;
                         default:
@@ -467,7 +468,7 @@ namespace ArdupilotMega
                         case (int)Common.ac2modes.ALT_HOLD:
                         case (int)Common.ac2modes.CIRCLE:
                         case (int)Common.ac2modes.POSITION:
-                            mode.base_mode = (byte)MAVLink.MAV_MODE_FLAG.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
+                            mode.base_mode = (byte)MAVLink.MAV_MODE_FLAG.CUSTOM_MODE_ENABLED;
                             mode.custom_mode = (uint)(int)Enum.Parse(Common.getModes(), modein);
                             break;
                         default:
@@ -482,14 +483,14 @@ namespace ArdupilotMega
         }
 		
 		#else
-        public static bool translateMode(string modein, ref  MAVLink.__mavlink_set_nav_mode_t navmode, ref MAVLink.__mavlink_set_mode_t mode)
+        public static bool translateMode(string modein, ref  MAVLink.mavlink_set_nav_mode_t navmode, ref MAVLink.mavlink_set_mode_t mode)
         {
 
-            //MAVLink.__mavlink_set_nav_mode_t navmode = new MAVLink.__mavlink_set_nav_mode_t();
+            //MAVLink.mavlink_set_nav_mode_t navmode = new MAVLink.mavlink_set_nav_mode_t();
             navmode.target = MainV2.comPort.sysid;
             navmode.nav_mode = 255;
 
-            //MAVLink.__mavlink_set_mode_t mode = new MAVLink.__mavlink_set_mode_t();
+            //MAVLink.mavlink_set_mode_t mode = new MAVLink.mavlink_set_mode_t();
             mode.target = MainV2.comPort.sysid;
 
             try
@@ -575,7 +576,10 @@ namespace ArdupilotMega
             try
             {
                 // this is for mono to a ssl server
-                ServicePointManager.CertificatePolicy = new NoCheckCertificatePolicy(); 
+                //ServicePointManager.CertificatePolicy = new NoCheckCertificatePolicy(); 
+
+                ServicePointManager.ServerCertificateValidationCallback =
+    new System.Net.Security.RemoteCertificateValidationCallback((sender, certificate, chain, policyErrors) => { return true; });
 
                 // Create a request using a URL that can receive a post. 
                 WebRequest request = WebRequest.Create(url);
diff --git a/Tools/ArdupilotMegaPlanner/CommsSerialPort.cs b/Tools/ArdupilotMegaPlanner/CommsSerialPort.cs
index ae5d6ef67752a09c2f497fa01dc8795e02b96fa3..2fe153f2898fefaed848b2008eaa3035423c6c6a 100644
--- a/Tools/ArdupilotMegaPlanner/CommsSerialPort.cs
+++ b/Tools/ArdupilotMegaPlanner/CommsSerialPort.cs
@@ -40,14 +40,14 @@ namespace ArdupilotMega
 
         public new static string[] GetPortNames()
         {
-            string[] monoDevs = new string[0];
+            List<string> allPorts = new List<string>();
 
             if (Directory.Exists("/dev/"))
             {
                 if (Directory.Exists("/dev/serial/by-id/"))
-                    monoDevs = Directory.GetFiles("/dev/serial/by-id/", "*");
-                monoDevs = Directory.GetFiles("/dev/", "*ACM*");
-                monoDevs = Directory.GetFiles("/dev/", "ttyUSB*");
+                    allPorts.AddRange(Directory.GetFiles("/dev/serial/by-id/", "*"));
+                allPorts.AddRange(Directory.GetFiles("/dev/", "ttyACM*"));
+                allPorts.AddRange(Directory.GetFiles("/dev/", "ttyUSB*"));
             }
 
             string[] ports = System.IO.Ports.SerialPort.GetPortNames()
@@ -55,12 +55,9 @@ namespace ArdupilotMega
             .Select(FixBlueToothPortNameBug)
             .ToArray();
 
-            string[] allPorts = new string[monoDevs.Length + ports.Length];
+            allPorts.AddRange(ports);
 
-            monoDevs.CopyTo(allPorts, 0);
-            ports.CopyTo(allPorts, monoDevs.Length);
-
-            return allPorts;
+            return allPorts.ToArray();
         }
 
 
diff --git a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackStageViewContentPanel.cs b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackStageViewContentPanel.cs
new file mode 100644
index 0000000000000000000000000000000000000000..d936dcec126e8f990a012a7a690e4f3e4a9f18b7
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackStageViewContentPanel.cs
@@ -0,0 +1,23 @@
+using System;
+using System.Collections.Generic;
+using System.Text;
+using System.Windows.Forms;
+
+namespace ArdupilotMega.Controls.BackstageView
+{
+    public class BackStageViewContentPanel : UserControl
+    {
+        public event FormClosingEventHandler FormClosing;
+
+        public void Close()
+        {
+            if (FormClosing != null)
+                FormClosing(this, new FormClosingEventArgs(CloseReason.UserClosing, false));
+        }
+
+        public new void OnLoad(EventArgs e)
+        {
+            base.OnLoad(e);
+        }
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackStageViewMenuPanel.cs b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackStageViewMenuPanel.cs
index 1a9ba583759cc56749a8523ad99e1b28fb808139..a7387c37d2d304f34b2430a7ebadb71d11c80970 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackStageViewMenuPanel.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackStageViewMenuPanel.cs
@@ -9,7 +9,7 @@ namespace ArdupilotMega.Controls.BackstageView
         internal Color GradColor = Color.White;
         internal Color PencilBorderColor = Color.White;
 
-        private const int GradientWidth = 6;
+        private const int GradientWidth = 20;
 
         public BackStageViewMenuPanel()
         {
@@ -29,5 +29,16 @@ namespace ArdupilotMega.Controls.BackstageView
 
             pevent.Graphics.DrawLine(new Pen(PencilBorderColor), Width-1,0,Width-1,Height);
         }
+
+        protected override void OnResize(System.EventArgs eventargs)
+        {
+            base.OnResize(eventargs);
+            this.Invalidate();
+        }
+
+        public void PaintBackground(PaintEventArgs pevent)
+        {
+            OnPaintBackground(pevent);
+        }
     }
 }
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.Designer.cs b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.Designer.cs
index 07546e1ac80bfd28f726043f6eaaa655735a6782..66d11286360422516a408a2a10e3f063da54a85a 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.Designer.cs
@@ -29,7 +29,7 @@
         private void InitializeComponent()
         {
             this.pnlPages = new System.Windows.Forms.Panel();
-            this.pnlMenu = new BackStageViewMenuPanel();
+            this.pnlMenu = new ArdupilotMega.Controls.BackstageView.BackStageViewMenuPanel();
             this.SuspendLayout();
             // 
             // pnlPages
@@ -37,10 +37,10 @@
             this.pnlPages.Anchor = ((System.Windows.Forms.AnchorStyles)((((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Bottom) 
             | System.Windows.Forms.AnchorStyles.Left) 
             | System.Windows.Forms.AnchorStyles.Right)));
-            this.pnlPages.Location = new System.Drawing.Point(147, 0);
+            this.pnlPages.Location = new System.Drawing.Point(150, 0);
             this.pnlPages.MinimumSize = new System.Drawing.Size(100, 0);
             this.pnlPages.Name = "pnlPages";
-            this.pnlPages.Size = new System.Drawing.Size(243, 189);
+            this.pnlPages.Size = new System.Drawing.Size(297, 192);
             this.pnlPages.TabIndex = 0;
             // 
             // pnlMenu
@@ -49,7 +49,7 @@
             | System.Windows.Forms.AnchorStyles.Left)));
             this.pnlMenu.Location = new System.Drawing.Point(0, 0);
             this.pnlMenu.Name = "pnlMenu";
-            this.pnlMenu.Size = new System.Drawing.Size(150, 170);
+            this.pnlMenu.Size = new System.Drawing.Size(150, 192);
             this.pnlMenu.TabIndex = 1;
             // 
             // BackstageView
@@ -60,7 +60,7 @@
             this.Controls.Add(this.pnlMenu);
             this.Controls.Add(this.pnlPages);
             this.Name = "BackstageView";
-            this.Size = new System.Drawing.Size(393, 192);
+            this.Size = new System.Drawing.Size(448, 192);
             this.ResumeLayout(false);
 
         }
diff --git a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs
index 2970e499b6e1d8e80aec3683504c1dc07c194950..e84bb86cc685602d932a0fe93bccfb4ed8888735 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageView.cs
@@ -22,6 +22,9 @@ namespace ArdupilotMega.Controls.BackstageView
         private const int ButtonSpacing = 30;
         private const int ButtonHeight = 30;
 
+        public BackstageViewPage SelectedPage { get { return _activePage; } }
+        public List<BackstageViewPage> Pages { get { return _pages; } }
+
         public BackstageView()
         {
             InitializeComponent();
@@ -160,7 +163,6 @@ namespace ArdupilotMega.Controls.BackstageView
                 _activePage = page;
 
             ActivatePage(page);
-            // Todo: set the link button to be selected looking 
         }
 
         private void CreateLinkButton(BackstageViewPage page)
@@ -192,7 +194,7 @@ namespace ArdupilotMega.Controls.BackstageView
             this.ActivatePage(associatedPage);
         }
 
-        private void ActivatePage(BackstageViewPage associatedPage)
+        public void ActivatePage(BackstageViewPage associatedPage)
         {
             // deactivate the old page
             _activePage.Page.Visible = false;
@@ -204,18 +206,27 @@ namespace ArdupilotMega.Controls.BackstageView
             newButton.IsSelected = true;
 
             _activePage = associatedPage;
+
+            _activePage.Page.OnLoad(new EventArgs());
         }
 
+        public void Close()
+        {
+            foreach (BackstageViewPage page in _pages)
+            {
+                page.Page.Close();
+            }
+        }
 
         public class BackstageViewPage
-        {
-            public BackstageViewPage(Control page, string linkText)
+        {            
+            public BackstageViewPage(BackStageViewContentPanel page, string linkText)
             {
                 Page = page;
                 LinkText = linkText;
             }
 
-            public Control Page { get; private set; }
+            public BackStageViewContentPanel Page { get; private set; }
             public string LinkText { get; set; }
         }
     }
diff --git a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageViewButton.cs b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageViewButton.cs
index 7f384a5bcd68edcda0fca6f34a0cf337e66a069f..ab6544584a62e7cc4c77659f61700e0c7a4a36ed 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageViewButton.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/BackstageView/BackstageViewButton.cs
@@ -22,10 +22,15 @@ namespace ArdupilotMega.Controls.BackstageView
 
         public BackstageViewButton()
         {
-            SetStyle(ControlStyles.SupportsTransparentBackColor, true);
-            SetStyle(ControlStyles.Opaque, true);
+            this.SuspendLayout();
+
             SetStyle(ControlStyles.ResizeRedraw, true);
-            this.BackColor = Color.Transparent;
+
+            this.Width = 150;
+            this.Height = 30;
+
+            
+            this.ResumeLayout(false);
         }
 
         /// <summary>
@@ -39,28 +44,26 @@ namespace ArdupilotMega.Controls.BackstageView
                 if (_isSelected != value)
                 {
                     _isSelected = value;
-                    //this.Parent.Refresh(); // <-- brutal, but works
-
-                   
-                    InvalidateParentForBackground();
 
                     this.Invalidate();
                 }
             }
         }
 
-        // Must be a better way to redraw parent control in the area of
-        // the button 
-        private void InvalidateParentForBackground()
+        protected override void OnPaintBackground(PaintEventArgs pevent)
         {
-            var screenrect = this.RectangleToScreen(this.ClientRectangle);
-            var rectangleToClient = this.Parent.RectangleToClient(screenrect);
-            this.Parent.Invalidate(rectangleToClient);
+            base.OnPaintBackground(pevent);
         }
 
+        protected override void OnResize(EventArgs e)
+        {
+            base.OnResize(e);
+        }
 
         protected override void OnPaint(PaintEventArgs pevent)
         {
+           ((BackStageViewMenuPanel)this.Parent).PaintBackground(pevent);
+
            Graphics g = pevent.Graphics;
          
 
@@ -122,7 +125,6 @@ namespace ArdupilotMega.Controls.BackstageView
         {
             _isMouseOver = true;
             base.OnMouseEnter(e);
-            InvalidateParentForBackground();
             this.Invalidate();
         }
 
@@ -130,12 +132,11 @@ namespace ArdupilotMega.Controls.BackstageView
         {
             _isMouseOver = false;
             base.OnMouseLeave(e);
-            InvalidateParentForBackground();
             this.Invalidate();
 
         }
-
-        // This IS necessary for transparency 
+        /*
+        // This IS necessary for transparency - windows only..... remove it
         protected override CreateParams CreateParams
         {
             get
@@ -146,5 +147,6 @@ namespace ArdupilotMega.Controls.BackstageView
                 return cp;
             }
         }
+         */
     }
 }
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs b/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs
index 71b2f5f0d245e064fe96f23dc4461b988499aad0..08863d1bd051c7480cdbd363a40edc085f845e36 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs
@@ -121,11 +121,6 @@ namespace System.Windows.Forms
             return answer;
         }
 
-        static void msgBoxFrm_FormClosing(object sender, FormClosingEventArgs e)
-        {
-            throw new NotImplementedException();
-        }
-
         // from http://stackoverflow.com/questions/2512781/winforms-big-paragraph-tooltip/2512895#2512895
         private static int maximumSingleLineTooltipLength = 85;
 
diff --git a/Tools/ArdupilotMegaPlanner/CurrentState.cs b/Tools/ArdupilotMegaPlanner/CurrentState.cs
index 420b4544b359ca5113807a47ccc0c79e734cf15d..087c85741d8fed233660bf0ae3e685ceb5d07111 100644
--- a/Tools/ArdupilotMegaPlanner/CurrentState.cs
+++ b/Tools/ArdupilotMegaPlanner/CurrentState.cs
@@ -252,6 +252,15 @@ namespace ArdupilotMega
         public float brklevel { get; set; }
         public int armed { get; set; }
 
+        // 3dr radio
+        public float rssi { get; set; }
+        public float remrssi { get; set; }
+        public byte txbuffer { get; set; }
+        public float noise { get; set; }
+        public float remnoise { get; set; }
+        public ushort rxerrors { get; set; }
+        public ushort fixedp { get; set; }
+
         // stats
         public ushort packetdropremote { get; set; }
         public ushort linkqualitygcs { get; set; }
@@ -334,7 +343,7 @@ namespace ArdupilotMega
 
                 if (bytearray != null) // hil
                 {
-                    var hil = bytearray.ByteArrayToStructure<MAVLink.__mavlink_rc_channels_scaled_t>(6);
+                    var hil = bytearray.ByteArrayToStructure<MAVLink.mavlink_rc_channels_scaled_t>(6);
 
                     hilch1 = hil.chan1_scaled;
                     hilch2 = hil.chan2_scaled;
@@ -352,7 +361,7 @@ namespace ArdupilotMega
 
                 if (bytearray != null)
                 {
-                    var nav = bytearray.ByteArrayToStructure<MAVLink.__mavlink_nav_controller_output_t>(6);
+                    var nav = bytearray.ByteArrayToStructure<MAVLink.mavlink_nav_controller_output_t>(6);
 
                     nav_roll = nav.nav_roll;
                     nav_pitch = nav.nav_pitch;
@@ -371,15 +380,15 @@ namespace ArdupilotMega
                 bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_HEARTBEAT];
                 if (bytearray != null)
                 {
-                    var hb = bytearray.ByteArrayToStructure<MAVLink.__mavlink_heartbeat_t>(6);
+                    var hb = bytearray.ByteArrayToStructure<MAVLink.mavlink_heartbeat_t>(6);
 
                     string oldmode = mode;
 
                     mode = "Unknown";
 
-                    if ((hb.base_mode & (byte)MAVLink.MAV_MODE_FLAG.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) != 0)
+                    if ((hb.base_mode & (byte)MAVLink.MAV_MODE_FLAG.CUSTOM_MODE_ENABLED) != 0)
                     {
-                        if (hb.type == (byte)MAVLink.MAV_TYPE.MAV_TYPE_FIXED_WING)
+                        if (hb.type == (byte)MAVLink.MAV_TYPE.FIXED_WING)
                         {
                             switch (hb.custom_mode)
                             {
@@ -415,7 +424,7 @@ namespace ArdupilotMega
                                     break;
                             }
                         }
-                        else if (hb.type == (byte)MAVLink.MAV_TYPE.MAV_TYPE_QUADROTOR) 
+                        else if (hb.type == (byte)MAVLink.MAV_TYPE.QUADROTOR) 
                         {
                             switch (hb.custom_mode)
                             {
@@ -453,9 +462,9 @@ namespace ArdupilotMega
                         }
                     }
 
-                    if (oldmode != mode && MainV2.speechenable && MainV2.getConfig("speechmodeenabled") == "True")
+                    if (oldmode != mode && MainV2.speechEnable && MainV2.getConfig("speechmodeenabled") == "True")
                     {
-                        MainV2.talk.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechmode")));
+                        MainV2.speechEngine.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechmode")));
                     }
                 }
 
@@ -463,7 +472,7 @@ namespace ArdupilotMega
                 bytearray = mavinterface.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS];
                 if (bytearray != null)
                 {
-                    var sysstatus = bytearray.ByteArrayToStructure<MAVLink.__mavlink_sys_status_t>(6);
+                    var sysstatus = bytearray.ByteArrayToStructure<MAVLink.mavlink_sys_status_t>(6);
 
                     battery_voltage = sysstatus.voltage_battery;
                     battery_remaining = sysstatus.battery_remaining;
@@ -478,7 +487,7 @@ namespace ArdupilotMega
 
                 if (bytearray != null)
                 {
-                    var sysstatus = bytearray.ByteArrayToStructure<MAVLink.__mavlink_sys_status_t>(6);
+                    var sysstatus = bytearray.ByteArrayToStructure<MAVLink.mavlink_sys_status_t>(6);
 
                     armed = sysstatus.status;
 
@@ -595,7 +604,7 @@ namespace ArdupilotMega
                 bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_PRESSURE];
                 if (bytearray != null)
                 {
-                    var pres = bytearray.ByteArrayToStructure<MAVLink.__mavlink_scaled_pressure_t>(6);
+                    var pres = bytearray.ByteArrayToStructure<MAVLink.mavlink_scaled_pressure_t>(6);
                     press_abs = pres.press_abs;
                     press_temp = pres.temperature;
                 }
@@ -603,7 +612,7 @@ namespace ArdupilotMega
                 bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SENSOR_OFFSETS];
                 if (bytearray != null)
                 {
-                    var sensofs = bytearray.ByteArrayToStructure<MAVLink.__mavlink_sensor_offsets_t>(6);
+                    var sensofs = bytearray.ByteArrayToStructure<MAVLink.mavlink_sensor_offsets_t>(6);
 
                     mag_ofs_x = sensofs.mag_ofs_x;
                     mag_ofs_y = sensofs.mag_ofs_y;
@@ -627,7 +636,7 @@ namespace ArdupilotMega
 
                 if (bytearray != null)
                 {
-                    var att = bytearray.ByteArrayToStructure<MAVLink.__mavlink_attitude_t>(6);
+                    var att = bytearray.ByteArrayToStructure<MAVLink.mavlink_attitude_t>(6);
 
                     roll = att.roll * rad2deg;
                     pitch = att.pitch * rad2deg;
@@ -641,7 +650,7 @@ namespace ArdupilotMega
                 bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW_INT];
                 if (bytearray != null)
                 {
-                    var gps = bytearray.ByteArrayToStructure<MAVLink.__mavlink_gps_raw_int_t>(6);
+                    var gps = bytearray.ByteArrayToStructure<MAVLink.mavlink_gps_raw_int_t>(6);
 
                     lat = gps.lat * 1.0e-7f;
                     lng = gps.lon * 1.0e-7f;
@@ -662,7 +671,7 @@ namespace ArdupilotMega
                 bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW];
                 if (bytearray != null)
                 {
-                    var gps = bytearray.ByteArrayToStructure<MAVLink.__mavlink_gps_raw_t>(6);
+                    var gps = bytearray.ByteArrayToStructure<MAVLink.mavlink_gps_raw_t>(6);
 
                     lat = gps.lat;
                     lng = gps.lon;
@@ -683,15 +692,27 @@ namespace ArdupilotMega
                 bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS];
                 if (bytearray != null)
                 {
-                    var gps = bytearray.ByteArrayToStructure<MAVLink.__mavlink_gps_status_t>(6);
+                    var gps = bytearray.ByteArrayToStructure<MAVLink.mavlink_gps_status_t>(6);
                     satcount = gps.satellites_visible;
                 }
 
+                bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RADIO];
+                if (bytearray != null)
+                {
+                    var radio = bytearray.ByteArrayToStructure<MAVLink.mavlink_radio_t>(6);
+                    rssi = radio.rssi;
+                    remrssi = radio.remrssi;
+                    txbuffer = radio.txbuf;
+                    rxerrors = radio.rxerrors;
+                    noise  = radio.noise;
+                    remnoise = radio.remnoise;
+                    fixedp = radio.fixedp;
+                }
 
                 bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT];
                 if (bytearray != null)
                 {
-                    var loc = bytearray.ByteArrayToStructure<MAVLink.__mavlink_global_position_int_t>(6);
+                    var loc = bytearray.ByteArrayToStructure<MAVLink.mavlink_global_position_int_t>(6);
 
                     //alt = loc.alt / 1000.0f;
                     lat = loc.lat / 10000000.0f;
@@ -701,15 +722,15 @@ namespace ArdupilotMega
                 bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_MISSION_CURRENT];
                 if (bytearray != null)
                 {
-                    var wpcur = bytearray.ByteArrayToStructure<MAVLink.__mavlink_mission_current_t>(6);
+                    var wpcur = bytearray.ByteArrayToStructure<MAVLink.mavlink_mission_current_t>(6);
               
                     int oldwp = (int)wpno;
 
                     wpno = wpcur.seq;
 
-                    if (oldwp != wpno && MainV2.speechenable && MainV2.getConfig("speechwaypointenabled") == "True")
+                    if (oldwp != wpno && MainV2.speechEnable && MainV2.getConfig("speechwaypointenabled") == "True")
                     {
-                        MainV2.talk.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechwaypoint")));
+                        MainV2.speechEngine.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechwaypoint")));
                     }
 
                     //MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT] = null;
@@ -719,7 +740,7 @@ namespace ArdupilotMega
                 bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION];
                 if (bytearray != null)
                 {
-                    var loc = bytearray.ByteArrayToStructure<MAVLink.__mavlink_global_position_t>(6);
+                    var loc = bytearray.ByteArrayToStructure<MAVLink.mavlink_global_position_t>(6);
                     alt = loc.alt;
                     lat = loc.lat;
                     lng = loc.lon;
@@ -728,7 +749,7 @@ namespace ArdupilotMega
                 bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT];
                 if (bytearray != null)
                 {
-                    var wpcur = bytearray.ByteArrayToStructure<MAVLink.__mavlink_waypoint_current_t>(6);
+                    var wpcur = bytearray.ByteArrayToStructure<MAVLink.mavlink_waypoint_current_t>(6);
 
                     int oldwp = (int)wpno;
 
@@ -746,7 +767,7 @@ namespace ArdupilotMega
                 bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW];
                 if (bytearray != null)
                 {
-                    var rcin = bytearray.ByteArrayToStructure<MAVLink.__mavlink_rc_channels_raw_t>(6);
+                    var rcin = bytearray.ByteArrayToStructure<MAVLink.mavlink_rc_channels_raw_t>(6);
 
                     ch1in = rcin.chan1_raw;
                     ch2in = rcin.chan2_raw;
@@ -763,7 +784,7 @@ namespace ArdupilotMega
                 bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW];
                 if (bytearray != null)
                 {
-                    var servoout = bytearray.ByteArrayToStructure<MAVLink.__mavlink_servo_output_raw_t>(6);
+                    var servoout = bytearray.ByteArrayToStructure<MAVLink.mavlink_servo_output_raw_t>(6);
 
                     ch1out = servoout.servo1_raw;
                     ch2out = servoout.servo2_raw;
@@ -781,7 +802,7 @@ namespace ArdupilotMega
                 bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU];
                 if (bytearray != null)
                 {
-                    var imu = bytearray.ByteArrayToStructure<MAVLink.__mavlink_raw_imu_t>(6);
+                    var imu = bytearray.ByteArrayToStructure<MAVLink.mavlink_raw_imu_t>(6);
 
                     gx = imu.xgyro;
                     gy = imu.ygyro;
@@ -801,7 +822,7 @@ namespace ArdupilotMega
                 bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_IMU];
                 if (bytearray != null)
                 {
-                    var imu = bytearray.ByteArrayToStructure<MAVLink.__mavlink_scaled_imu_t>(6);
+                    var imu = bytearray.ByteArrayToStructure<MAVLink.mavlink_scaled_imu_t>(6);
 
                     gx = imu.xgyro;
                     gy = imu.ygyro;
@@ -818,7 +839,7 @@ namespace ArdupilotMega
                 bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD];
                 if (bytearray != null)
                 {
-                    var vfr = bytearray.ByteArrayToStructure<MAVLink.__mavlink_vfr_hud_t>(6);
+                    var vfr = bytearray.ByteArrayToStructure<MAVLink.mavlink_vfr_hud_t>(6);
 
                     groundspeed = vfr.groundspeed;
                     airspeed = vfr.airspeed;
@@ -843,7 +864,7 @@ namespace ArdupilotMega
                 bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_MEMINFO];
                 if (bytearray != null)
                 {
-                    var mem = bytearray.ByteArrayToStructure<MAVLink.__mavlink_meminfo_t>(6);
+                    var mem = bytearray.ByteArrayToStructure<MAVLink.mavlink_meminfo_t>(6);
                     freemem = mem.freemem;
                     brklevel = mem.brkval;
                 }
diff --git a/Tools/ArdupilotMegaPlanner/Driver/Arduino MEGA 2560.inf b/Tools/ArdupilotMegaPlanner/Driver/Arduino MEGA 2560.inf
new file mode 100644
index 0000000000000000000000000000000000000000..7053f3b95f9f6863f3ed36c2238f334783e2ff99
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Driver/Arduino MEGA 2560.inf	
@@ -0,0 +1,106 @@
+;************************************************************
+; Windows USB CDC ACM Setup File
+; Copyright (c) 2000 Microsoft Corporation
+
+
+[Version]
+Signature="$Windows NT$"
+Class=Ports
+ClassGuid={4D36E978-E325-11CE-BFC1-08002BE10318}
+Provider=%MFGNAME%
+LayoutFile=layout.inf
+CatalogFile=%MFGFILENAME%.cat
+DriverVer=11/15/2007,5.1.2600.0
+
+[Manufacturer]
+%MFGNAME%=DeviceList, NTamd64
+
+[DestinationDirs]
+DefaultDestDir=12
+
+
+;------------------------------------------------------------------------------
+;  Windows 2000/XP/Vista-32bit Sections
+;------------------------------------------------------------------------------
+
+[DriverInstall.nt]
+include=mdmcpq.inf
+CopyFiles=DriverCopyFiles.nt
+AddReg=DriverInstall.nt.AddReg
+
+[DriverCopyFiles.nt]
+usbser.sys,,,0x20
+
+[DriverInstall.nt.AddReg]
+HKR,,DevLoader,,*ntkern
+HKR,,NTMPDriver,,%DRIVERFILENAME%.sys
+HKR,,EnumPropPages32,,"MsPorts.dll,SerialPortPropPageProvider"
+
+[DriverInstall.nt.Services]
+AddService=usbser, 0x00000002, DriverService.nt
+
+[DriverService.nt]
+DisplayName=%SERVICE%
+ServiceType=1
+StartType=3
+ErrorControl=1
+ServiceBinary=%12%\%DRIVERFILENAME%.sys
+
+;------------------------------------------------------------------------------
+;  Vista-64bit Sections
+;------------------------------------------------------------------------------
+
+[DriverInstall.NTamd64]
+include=mdmcpq.inf
+CopyFiles=DriverCopyFiles.NTamd64
+AddReg=DriverInstall.NTamd64.AddReg
+
+[DriverCopyFiles.NTamd64]
+%DRIVERFILENAME%.sys,,,0x20
+
+[DriverInstall.NTamd64.AddReg]
+HKR,,DevLoader,,*ntkern
+HKR,,NTMPDriver,,%DRIVERFILENAME%.sys
+HKR,,EnumPropPages32,,"MsPorts.dll,SerialPortPropPageProvider"
+
+[DriverInstall.NTamd64.Services]
+AddService=usbser, 0x00000002, DriverService.NTamd64
+
+[DriverService.NTamd64]
+DisplayName=%SERVICE%
+ServiceType=1
+StartType=3
+ErrorControl=1
+ServiceBinary=%12%\%DRIVERFILENAME%.sys
+
+
+;------------------------------------------------------------------------------
+;  Vendor and Product ID Definitions
+;------------------------------------------------------------------------------
+; When developing your USB device, the VID and PID used in the PC side
+; application program and the firmware on the microcontroller must match.
+; Modify the below line to use your VID and PID.  Use the format as shown below.
+; Note: One INF file can be used for multiple devices with different VID and PIDs.
+; For each supported device, append ",USB\VID_xxxx&PID_yyyy" to the end of the line.
+;------------------------------------------------------------------------------
+[SourceDisksFiles]
+[SourceDisksNames]
+[DeviceList]
+%DESCRIPTION%=DriverInstall, USB\VID_2341&PID_0010
+
+[DeviceList.NTamd64]
+%DESCRIPTION%=DriverInstall, USB\VID_2341&PID_0010
+
+
+;------------------------------------------------------------------------------
+;  String Definitions
+;------------------------------------------------------------------------------
+;Modify these strings to customize your device
+;------------------------------------------------------------------------------
+[Strings]
+MFGFILENAME="CDC_vista"
+DRIVERFILENAME ="usbser"
+MFGNAME="Arduino LLC (www.arduino.cc)"
+INSTDISK="Arduino Mega 2560 Driver Installer"
+DESCRIPTION="Arduino Mega 2560"
+SERVICE="USB RS-232 Emulation Driver"
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml
index 7b8433162d1c712f94833d478d214079cc6bd912..178955920a2956c4238b0f5680b822bdef53671a 100644
--- a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml
+++ b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml
@@ -4,7 +4,7 @@
     <url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.hex</url>
     <url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.hex</url2560>
     <url2560-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560-2.hex</url2560-2>
-    <name>ArduPlane V2.32  </name>
+    <name>ArduPlane V2.33  </name>
     <desc></desc>
     <format_version>12</format_version>
   </Firmware>
@@ -12,7 +12,7 @@
     <url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.hex</url>
     <url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.hex</url2560>
     <url2560-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560-2.hex</url2560-2>
-    <name>ArduPlane V2.32 HIL</name>
+    <name>ArduPlane V2.33 HIL</name>
     <desc>
 #define FLIGHT_MODE_CHANNEL	8
 #define FLIGHT_MODE_1		AUTO
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs
index 853d0d4ca1e0580a8b998d0b3822441514e31d43..2c875ef6449a259d14d380575b603884e173827d 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs
@@ -579,7 +579,6 @@ namespace ArdupilotMega.GCSViews
                 }
             }
             catch { ((Control)text[0]).BackColor = Color.Red; }
-
             Params.Focus();
         }
 
@@ -593,29 +592,11 @@ namespace ArdupilotMega.GCSViews
             DialogResult dr = ofd.ShowDialog();
             if (dr == DialogResult.OK)
             {
-                StreamReader sr = new StreamReader(ofd.OpenFile());
-                while (!sr.EndOfStream)
-                {
-                    string line = sr.ReadLine();
-
-                    if (line.Contains("NOTE:"))
-                        CustomMessageBox.Show(line, "Saved Note");
-
-                    int index = line.IndexOf(',');
-
-                    int index2 = line.IndexOf(',', index + 1);
-
-                    if (index == -1)
-                        continue;
-
-                    if (index2 != -1)
-                        line = line.Replace(',', '.');
-
-                    string name = line.Substring(0, index);
-                    float value = float.Parse(line.Substring(index + 1), new System.Globalization.CultureInfo("en-US"));
-
-                    MAVLink.modifyParamForDisplay(true, name, ref value);
+                Hashtable param2 = loadParamFile(ofd.FileName);
 
+                foreach (string name in param2.Keys)
+                {
+                    string value = param2[name].ToString();
                     // set param table as well
                     foreach (DataGridViewRow row in Params.Rows)
                     {
@@ -647,7 +628,6 @@ namespace ArdupilotMega.GCSViews
                         }
                     }
                 }
-                sr.Close();
             }
         }
 
@@ -731,17 +711,8 @@ namespace ArdupilotMega.GCSViews
         {
             if (ConfigTabs.SelectedTab == TabSetup)
             {
-                if (!MainV2.comPort.BaseStream.IsOpen)
-                {
-                    CustomMessageBox.Show("Please Connect First");
-                    ConfigTabs.SelectedIndex = 0;
-                }
-                else
-                {
-
-                    Setup.Setup temp = new Setup.Setup();
 
-                    temp.Configuration = this;
+                    GCSViews.ConfigurationView.Setup temp = new GCSViews.ConfigurationView.Setup();
 
                     ThemeManager.ApplyThemeTo(temp);
 
@@ -750,7 +721,6 @@ namespace ArdupilotMega.GCSViews
                     startup = true;
                     processToScreen();
                     startup = false;
-                }
             }
         }
 
@@ -1125,39 +1095,65 @@ namespace ArdupilotMega.GCSViews
             DialogResult dr = ofd.ShowDialog();
             if (dr == DialogResult.OK)
             {
-                StreamReader sr = new StreamReader(ofd.OpenFile());
-                while (!sr.EndOfStream)
-                {
-                    string line = sr.ReadLine();
+                param2 = loadParamFile(ofd.FileName);
 
-                    if (line.Contains("NOTE:"))
-                        CustomMessageBox.Show(line, "Saved Note");
+                ParamCompare temp = new ParamCompare(Params, param, param2);
+                ThemeManager.ApplyThemeTo(temp);
+                temp.ShowDialog();
+            }
+        }
 
-                    int index = line.IndexOf(',');
+        Hashtable loadParamFile(string Filename)
+        {
+            Hashtable param = new Hashtable();
 
-                    if (index == -1)
-                        continue;
+            StreamReader sr = new StreamReader(Filename);
+            while (!sr.EndOfStream)
+            {
+                string line = sr.ReadLine();
 
-                    string name = line.Substring(0, index);
-                    float value = float.Parse(line.Substring(index + 1), new System.Globalization.CultureInfo("en-US"));
+                if (line.Contains("NOTE:"))
+                    CustomMessageBox.Show(line, "Saved Note");
 
-                    MAVLink.modifyParamForDisplay(true, name, ref value);
+                if (line.StartsWith("#"))
+                    continue;
 
-                    if (name == "SYSID_SW_MREV")
-                        continue;
-                    if (name == "WP_TOTAL")
-                        continue;
-                    if (name == "CMD_TOTAL")
-                        continue;
+                string[] items = line.Split(new char[] {' ', ',', '\t' },StringSplitOptions.RemoveEmptyEntries);
 
-                    param2[name] = value;
-                }
-                sr.Close();
+                if (items.Length != 2)
+                    continue;
 
-                ParamCompare temp = new ParamCompare(this, param, param2);
-                ThemeManager.ApplyThemeTo(temp);
-                temp.ShowDialog();
+                string name = items[0];
+                float value = float.Parse(items[1], new System.Globalization.CultureInfo("en-US"));
+
+                MAVLink.modifyParamForDisplay(true, name, ref value);
+
+                if (name == "SYSID_SW_MREV")
+                    continue;
+                if (name == "WP_TOTAL")
+                    continue;
+                if (name == "CMD_TOTAL")
+                    continue;
+                if (name == "FENCE_TOTAL")
+                    continue;
+                if (name == "SYS_NUM_RESETS")
+                    continue;
+                if (name == "ARSPD_OFFSET")
+                    continue;
+                if (name == "GND_ABS_PRESS")
+                    continue;
+                if (name == "GND_TEMP")
+                    continue;
+                if (name == "CMD_INDEX")
+                    continue;
+                if (name == "LOG_LASTFILE")
+                    continue;
+
+                param[name] = value;
             }
+            sr.Close();
+
+            return param;
         }
 
         private void CHK_GDIPlus_CheckedChanged(object sender, EventArgs e)
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.Designer.cs
new file mode 100644
index 0000000000000000000000000000000000000000..1304694720a24790d672c1488daf9f2a4903f84d
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.Designer.cs
@@ -0,0 +1,110 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    partial class ConfigAccelerometerCalibration
+    {
+        /// <summary> 
+        /// Required designer variable.
+        /// </summary>
+        private System.ComponentModel.IContainer components = null;
+
+        /// <summary> 
+        /// Clean up any resources being used.
+        /// </summary>
+        /// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
+        protected override void Dispose(bool disposing)
+        {
+            if (disposing && (components != null))
+            {
+                components.Dispose();
+            }
+            base.Dispose(disposing);
+        }
+
+        #region Component Designer generated code
+
+        /// <summary> 
+        /// Required method for Designer support - do not modify 
+        /// the contents of this method with the code editor.
+        /// </summary>
+        private void InitializeComponent()
+        {
+            System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigAccelerometerCalibration));
+            this.label28 = new System.Windows.Forms.Label();
+            this.label16 = new System.Windows.Forms.Label();
+            this.label15 = new System.Windows.Forms.Label();
+            this.pictureBoxQuadX = new System.Windows.Forms.PictureBox();
+            this.pictureBoxQuad = new System.Windows.Forms.PictureBox();
+            this.BUT_levelac2 = new ArdupilotMega.MyButton();
+            ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).BeginInit();
+            this.SuspendLayout();
+            // 
+            // label28
+            // 
+            resources.ApplyResources(this.label28, "label28");
+            this.label28.Name = "label28";
+            // 
+            // label16
+            // 
+            resources.ApplyResources(this.label16, "label16");
+            this.label16.Name = "label16";
+            // 
+            // label15
+            // 
+            resources.ApplyResources(this.label15, "label15");
+            this.label15.Name = "label15";
+            // 
+            // pictureBoxQuadX
+            // 
+            this.pictureBoxQuadX.Cursor = System.Windows.Forms.Cursors.Hand;
+            this.pictureBoxQuadX.Image = global::ArdupilotMega.Properties.Resources.quadx;
+            resources.ApplyResources(this.pictureBoxQuadX, "pictureBoxQuadX");
+            this.pictureBoxQuadX.Name = "pictureBoxQuadX";
+            this.pictureBoxQuadX.TabStop = false;
+            this.pictureBoxQuadX.Click += new System.EventHandler(this.pictureBoxQuadX_Click);
+            // 
+            // pictureBoxQuad
+            // 
+            this.pictureBoxQuad.Cursor = System.Windows.Forms.Cursors.Hand;
+            this.pictureBoxQuad.Image = global::ArdupilotMega.Properties.Resources.quad;
+            resources.ApplyResources(this.pictureBoxQuad, "pictureBoxQuad");
+            this.pictureBoxQuad.Name = "pictureBoxQuad";
+            this.pictureBoxQuad.TabStop = false;
+            this.pictureBoxQuad.Click += new System.EventHandler(this.pictureBoxQuad_Click);
+            // 
+            // BUT_levelac2
+            // 
+            resources.ApplyResources(this.BUT_levelac2, "BUT_levelac2");
+            this.BUT_levelac2.Name = "BUT_levelac2";
+            this.BUT_levelac2.UseVisualStyleBackColor = true;
+            this.BUT_levelac2.Click += new System.EventHandler(this.BUT_levelac2_Click);
+            // 
+            // ConfigAccelerometerCalibration
+            // 
+            resources.ApplyResources(this, "$this");
+            this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+            this.Controls.Add(this.label28);
+            this.Controls.Add(this.label16);
+            this.Controls.Add(this.label15);
+            this.Controls.Add(this.pictureBoxQuadX);
+            this.Controls.Add(this.pictureBoxQuad);
+            this.Controls.Add(this.BUT_levelac2);
+            this.Name = "ConfigAccelerometerCalibration";
+            this.Load += new System.EventHandler(this.ConfigAccelerometerCalibration_Load);
+            ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).EndInit();
+            this.ResumeLayout(false);
+            this.PerformLayout();
+
+        }
+
+        #endregion
+
+        private System.Windows.Forms.Label label28;
+        private System.Windows.Forms.Label label16;
+        private System.Windows.Forms.Label label15;
+        private System.Windows.Forms.PictureBox pictureBoxQuadX;
+        private System.Windows.Forms.PictureBox pictureBoxQuad;
+        private MyButton BUT_levelac2;
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.cs
new file mode 100644
index 0000000000000000000000000000000000000000..c4023e5b5c1a8eaca4af6b3e622df05bf1567da7
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.cs
@@ -0,0 +1,72 @@
+using System;
+using System.Collections.Generic;
+using System.ComponentModel;
+using System.Drawing;
+using System.Data;
+using System.Linq;
+using System.Text;
+using System.Windows.Forms;
+using ArdupilotMega.Controls.BackstageView;
+
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    public partial class ConfigAccelerometerCalibration : BackStageViewContentPanel
+    {
+        public ConfigAccelerometerCalibration()
+        {
+            InitializeComponent();
+        }
+
+        private void pictureBoxQuadX_Click(object sender, EventArgs e)
+        {
+            try
+            {
+                MainV2.comPort.setParam("FRAME", 1f);
+                CustomMessageBox.Show("Set to x");
+            }
+            catch { CustomMessageBox.Show("Set frame failed"); }
+        }
+
+        private void BUT_levelac2_Click(object sender, EventArgs e)
+        {
+            try
+            {
+#if MAVLINK10
+                int fixme; // needs to be accel only
+                MainV2.comPort.doCommand(MAVLink.MAV_CMD.PREFLIGHT_CALIBRATION,1,1,1,1,1,1,1);
+#else
+                MainV2.comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_CALIBRATE_ACC);
+#endif
+
+                BUT_levelac2.Text = "Complete";
+            }
+            catch
+            {
+                CustomMessageBox.Show("Failed to level : ac2 2.0.37+ is required");
+            }
+        }
+
+        private void pictureBoxQuad_Click(object sender, EventArgs e)
+        {
+            try
+            {
+                MainV2.comPort.setParam("FRAME", 0f);
+                CustomMessageBox.Show("Set to +");
+            }
+            catch { CustomMessageBox.Show("Set frame failed"); }
+        }
+
+        private void ConfigAccelerometerCalibration_Load(object sender, EventArgs e)
+        {
+            if (!MainV2.comPort.BaseStream.IsOpen)
+            {
+                this.Enabled = false;
+                return;
+            }
+            else
+            {
+                this.Enabled = true;
+            }
+        }
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.es-ES.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.es-ES.resx
new file mode 100644
index 0000000000000000000000000000000000000000..70ad73f1af84a8cec236442b9c51462353fceab5
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.es-ES.resx
@@ -0,0 +1,315 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manual</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Modo actual:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Habilitar el flujo óptico</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>NOTA: Las imágenes son sólo para su presentación</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Actual:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APMSetup</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Swash-Servo posición</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Activar Compas</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Ajuste Chásis (+ or x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modos</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Reset</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Superior</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Swash de Viaje</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manual</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Timón de Viaje</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibración del sensor de voltaje:Para calibrar el sensor, use un multímetro para medir la tensión que sale de la CES de la batería-la eliminación del circuito (se trata de cables negro y rojo en el cable de tres hilos que suministra energía a la placa APM).Luego reste 0,3 V de ese valor y entrar en él en el campo # 1 a la izquierda.</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrar Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Modo de Vuelo 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Alabeo Max</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Modo de Vuelo 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Cabeceo Max</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>por ejemplo, en grados 2 ° 3 'W es -2,3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Modo de Vuelo 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Nivel tu quad para establecer las compensaciones por defecto acel</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Modo de Vuelo 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacidad</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Declinación</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Activar Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Entrada Radio</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibración</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Modo de Vuelo 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Modo de Vuelo 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Gyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Sitio Web Declinación</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batería</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Cero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Activar Airspeed</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Restablecer los Ajustes de hardware APM</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.fr.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.fr.resx
new file mode 100644
index 0000000000000000000000000000000000000000..1bd274beea2e052315a0ab1e83d3619dcf47cbf1
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.fr.resx
@@ -0,0 +1,312 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manuel</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Mode Courant:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Activ. capteur optique</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>NOTE: images pou presentation uniquement. Fonctionnel pour Hex, Octo etc...</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Actuel:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APMSetup</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Swash-Servo position</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Activ. Boussole</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>type de châssis (+ ou x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modes</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Réinit.</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Haut</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Mouvement Swash</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manuel</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Deplac. du Gouvernail</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibration du capteur de Voltage.1. Mesurer le voltage sur APM et inscrivez-le dans la boite ci-bas.2. Mesurer le voltage de la batterie et inscrivez-le dans la boite ci-bas.3. Inscrire les ampères par volt de la documentation du capteur de courant ci-bas</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrer Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Mode de vol 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Roulis Max</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Mode de vol 2</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Tangage Max</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>en degrés eg 2° 3' W est -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Mode de vol 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Niveler l'apareil pour copensation des accels</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Mode de vol 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacité</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Déclination</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Activer Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Entrée Radio</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Mode de vol 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Mode de vol 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Gyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Matériel</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Site Web Déclination</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batterie</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zéro</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Activ. Airspeed</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>RàZ tout parametres du APM</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Moniteur</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.it-IT.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.it-IT.resx
new file mode 100644
index 0000000000000000000000000000000000000000..2b2636c8132c76e5855c9dbb2c87151786f287c3
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.it-IT.resx
@@ -0,0 +1,318 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manuale</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Modo Corrente:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Abilita Flusso ottico</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>Nota: le immagini sono sono per presentazione, funzionerà con Hexa, etc.</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevatore CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Corrente:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>Imposta APM</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Posizione del servo del piatto</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Abilita Magnetometro</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Imposta Frame (+ or x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modi</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Riavvia</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Alto</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Escursione del piatto</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manuale</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Escursione Timone</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibarzione del sensore di voltaggio:
+1. Misura il valtaggio di ingresso di APM e inseriscilo nel box sotto 
+2. Misura il voltaggio della batteria e inseriscilo nel box sotto 
+3. Dalle caratteristiche del sensore di corrente, inserisci il valore degli ampere per volt nel box qui sotto</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrazione Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Massimo</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Modo di volo 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Rollio massimo</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Modo di volo 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Passo massimo</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>in gradi es 2° 3' W is -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Modo di volo 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Livella il quad per impostare gli accelerometri</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Modo di volo 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacità</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Declinazione</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Attiva Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Ingresso Radio</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibration</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Modo di volo 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Modo di volo 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Giroscopio</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Sito Web per la Declinazione</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batteria</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Attiva Sensore Velocità</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Resetta APM ai valori di Default</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.pl.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.pl.resx
new file mode 100644
index 0000000000000000000000000000000000000000..057b9327168c6471be22139b5d017e20582de843
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.pl.resx
@@ -0,0 +1,318 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Ręczne</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Aktualny tryb:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Włącz Optical Flow</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>UWAGA: Obrazy są wyłącznie do prezentacji, działają jedynie z hexa, itp.</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Odwr. Elevon CH1</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>Aktualny PWM:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>Ustawienia APM</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Pozycja serwa płyty ster.</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Włącz kompas</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Ustawienie ramy (+ lub x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Tryby</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Reset</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Góra</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Zakres ruchu płyty sterującej</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Ręczne</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Zakres steru kierunku</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Kalibracja czujnika napięcia:
+1. Zmierz napięcie wejściowe APM i wpisz poniżej
+2. Zmierz napięcie baterii i wpisz poniżej
+3. Wpisz poniżej ilość amperów/wolt [A/V] z dokumentacji czujnika prądu</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Kalibracja radia</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Tryb lotu 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Max przechylenie</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Tryb lotu 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Max pochylenie</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>w stopniech np. 2° 3' W to -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Tryb lotu 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Wypoziomuj quada żeby stawić domyśle offsety przysp.</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Tryb lotu 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Pojemność</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Deklinacja</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Włącz sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Wejścia radia</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibration</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Tryb lotu 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Tryb lotu 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Żyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Strona www deklinacji</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Bateria</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Włącz prędkość powietrza</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Reset APM do stawień domyślnych</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.resx
new file mode 100644
index 0000000000000000000000000000000000000000..d866d08ac01fea75663b3a82e8407c6c3c995daa
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.resx
@@ -0,0 +1,310 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
+  <data name="label28.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
+  <data name="label28.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="label28.Location" type="System.Drawing.Point, System.Drawing">
+    <value>124, 13</value>
+  </data>
+  <data name="label28.Size" type="System.Drawing.Size, System.Drawing">
+    <value>210, 13</value>
+  </data>
+  <data name="label28.TabIndex" type="System.Int32, mscorlib">
+    <value>15</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Level your quad to set default accel offsets</value>
+  </data>
+  <data name="&gt;&gt;label28.Name" xml:space="preserve">
+    <value>label28</value>
+  </data>
+  <data name="&gt;&gt;label28.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label28.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label28.ZOrder" xml:space="preserve">
+    <value>0</value>
+  </data>
+  <data name="label16.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label16.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label16.Location" type="System.Drawing.Point, System.Drawing">
+    <value>124, 308</value>
+  </data>
+  <data name="label16.Size" type="System.Drawing.Size, System.Drawing">
+    <value>192, 26</value>
+  </data>
+  <data name="label16.TabIndex" type="System.Int32, mscorlib">
+    <value>13</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>NOTE: images are for presentation only
+will work with hexa's etc</value>
+  </data>
+  <data name="&gt;&gt;label16.Name" xml:space="preserve">
+    <value>label16</value>
+  </data>
+  <data name="&gt;&gt;label16.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label16.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label16.ZOrder" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="label15.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label15.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label15.Location" type="System.Drawing.Point, System.Drawing">
+    <value>167, 99</value>
+  </data>
+  <data name="label15.Size" type="System.Drawing.Size, System.Drawing">
+    <value>102, 13</value>
+  </data>
+  <data name="label15.TabIndex" type="System.Int32, mscorlib">
+    <value>12</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Frame Setup (+ or x)</value>
+  </data>
+  <data name="&gt;&gt;label15.Name" xml:space="preserve">
+    <value>label15</value>
+  </data>
+  <data name="&gt;&gt;label15.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label15.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label15.ZOrder" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="pictureBoxQuadX.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="pictureBoxQuadX.Location" type="System.Drawing.Point, System.Drawing">
+    <value>226, 115</value>
+  </data>
+  <data name="pictureBoxQuadX.Size" type="System.Drawing.Size, System.Drawing">
+    <value>190, 190</value>
+  </data>
+  <data name="pictureBoxQuadX.SizeMode" type="System.Windows.Forms.PictureBoxSizeMode, System.Windows.Forms">
+    <value>Zoom</value>
+  </data>
+  <data name="pictureBoxQuadX.TabIndex" type="System.Int32, mscorlib">
+    <value>11</value>
+  </data>
+  <data name="&gt;&gt;pictureBoxQuadX.Name" xml:space="preserve">
+    <value>pictureBoxQuadX</value>
+  </data>
+  <data name="&gt;&gt;pictureBoxQuadX.Type" xml:space="preserve">
+    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;pictureBoxQuadX.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;pictureBoxQuadX.ZOrder" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="pictureBoxQuad.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="pictureBoxQuad.Location" type="System.Drawing.Point, System.Drawing">
+    <value>19, 115</value>
+  </data>
+  <data name="pictureBoxQuad.Size" type="System.Drawing.Size, System.Drawing">
+    <value>190, 190</value>
+  </data>
+  <data name="pictureBoxQuad.SizeMode" type="System.Windows.Forms.PictureBoxSizeMode, System.Windows.Forms">
+    <value>Zoom</value>
+  </data>
+  <data name="pictureBoxQuad.TabIndex" type="System.Int32, mscorlib">
+    <value>10</value>
+  </data>
+  <data name="&gt;&gt;pictureBoxQuad.Name" xml:space="preserve">
+    <value>pictureBoxQuad</value>
+  </data>
+  <data name="&gt;&gt;pictureBoxQuad.Type" xml:space="preserve">
+    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;pictureBoxQuad.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;pictureBoxQuad.ZOrder" xml:space="preserve">
+    <value>4</value>
+  </data>
+  <data name="BUT_levelac2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="BUT_levelac2.Location" type="System.Drawing.Point, System.Drawing">
+    <value>181, 42</value>
+  </data>
+  <data name="BUT_levelac2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>75, 23</value>
+  </data>
+  <data name="BUT_levelac2.TabIndex" type="System.Int32, mscorlib">
+    <value>14</value>
+  </data>
+  <data name="BUT_levelac2.Text" xml:space="preserve">
+    <value>Level</value>
+  </data>
+  <data name="&gt;&gt;BUT_levelac2.Name" xml:space="preserve">
+    <value>BUT_levelac2</value>
+  </data>
+  <data name="&gt;&gt;BUT_levelac2.Type" xml:space="preserve">
+    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;BUT_levelac2.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;BUT_levelac2.ZOrder" xml:space="preserve">
+    <value>5</value>
+  </data>
+  <metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
+    <value>True</value>
+  </metadata>
+  <data name="$this.AutoScaleDimensions" type="System.Drawing.SizeF, System.Drawing">
+    <value>6, 13</value>
+  </data>
+  <data name="$this.Size" type="System.Drawing.Size, System.Drawing">
+    <value>439, 356</value>
+  </data>
+  <data name="&gt;&gt;$this.Name" xml:space="preserve">
+    <value>ConfigAccelerometerCalibration</value>
+  </data>
+  <data name="&gt;&gt;$this.Type" xml:space="preserve">
+    <value>ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.zh-Hans.resx
new file mode 100644
index 0000000000000000000000000000000000000000..f96892c423b112b28127ad582686f33464b57c5b
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.zh-Hans.resx
@@ -0,0 +1,496 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>遥控输入</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>模式</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>硬件</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>电池</value>
+  </data>
+  <data name="tabHeli.Text" xml:space="preserve">
+    <value>AC2 直升机</value>
+  </data>
+  <data name="groupBoxElevons.Text" xml:space="preserve">
+    <value>上降副翼 (Elevon) 配置</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="CHK_elevonch2rev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>115, 17</value>
+  </data>
+  <data name="CHK_elevonch2rev.Text" xml:space="preserve">
+    <value>Elevons CH2 逆转</value>
+  </data>
+  <data name="CHK_elevonrev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>91, 17</value>
+  </data>
+  <data name="CHK_elevonrev.Text" xml:space="preserve">
+    <value>Elevons 逆转</value>
+  </data>
+  <data name="CHK_elevonch1rev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>115, 17</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 逆转</value>
+  </data>
+  <data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch3.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch4.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch2.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch1.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>校准遥控</value>
+  </data>
+  <data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="label14.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>当前 PWM:</value>
+  </data>
+  <data name="label13.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>当前模式:</value>
+  </data>
+  <data name="label6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>飞行模式 6</value>
+  </data>
+  <data name="label5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>飞行模式 5</value>
+  </data>
+  <data name="label4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>飞行模式 4</value>
+  </data>
+  <data name="label3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>飞行模式 3</value>
+  </data>
+  <data name="label2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>飞行模式 2</value>
+  </data>
+  <data name="label1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>飞行模式 1</value>
+  </data>
+  <data name="BUT_SaveModes.Text" xml:space="preserve">
+    <value>保存模式</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>十进制, 2° 3' W 就是 -2.3</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>启用光流</value>
+  </data>
+  <data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
+    <value>67, 13</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>磁偏角网站</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>磁偏角</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>启用空速计</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>启用声纳</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>启用罗盘</value>
+  </data>
+  <data name="label31.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label31.Text" xml:space="preserve">
+    <value>输入电压:</value>
+  </data>
+  <data name="label32.Size" type="System.Drawing.Size, System.Drawing">
+    <value>94, 13</value>
+  </data>
+  <data name="label32.Text" xml:space="preserve">
+    <value>测量的电池电压:</value>
+  </data>
+  <data name="label33.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label33.Text" xml:space="preserve">
+    <value>电池电压:</value>
+  </data>
+  <data name="label34.Size" type="System.Drawing.Size, System.Drawing">
+    <value>52, 13</value>
+  </data>
+  <data name="label34.Text" xml:space="preserve">
+    <value>分 压 比:</value>
+  </data>
+  <data name="label35.Size" type="System.Drawing.Size, System.Drawing">
+    <value>63, 13</value>
+  </data>
+  <data name="label35.Text" xml:space="preserve">
+    <value>安培/伏特:</value>
+  </data>
+  <data name="label47.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 18</value>
+  </data>
+  <data name="label47.Text" xml:space="preserve">
+    <value>传感器</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>电压传感器校准:
+1. 测量APM输入电压,输入到下方的文本框中
+2. 测量电池电压,输入到下方的文本框中
+3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中</value>
+  </data>
+  <data name="label29.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>容量</value>
+  </data>
+  <data name="label30.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 13</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>监控器</value>
+  </data>
+  <data name="label28.Size" type="System.Drawing.Size, System.Drawing">
+    <value>175, 13</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>设置水平面的默认加速度计偏移</value>
+  </data>
+  <data name="label16.Size" type="System.Drawing.Size, System.Drawing">
+    <value>261, 13</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>注: 图片只是用于展示,设置可以用于六轴等机架</value>
+  </data>
+  <data name="label15.Size" type="System.Drawing.Size, System.Drawing">
+    <value>93, 13</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>机架设置 (+ 或 x)</value>
+  </data>
+  <data name="BUT_levelac2.Text" xml:space="preserve">
+    <value>找平</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>手动</value>
+  </data>
+  <data name="BUT_swash_manual.Text" xml:space="preserve">
+    <value>手动</value>
+  </data>
+  <data name="label46.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label46.Text" xml:space="preserve">
+    <value>感度</value>
+  </data>
+  <data name="label45.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label45.Text" xml:space="preserve">
+    <value>启用</value>
+  </data>
+  <data name="label44.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label44.Text" xml:space="preserve">
+    <value>微调</value>
+  </data>
+  <data name="label43.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label43.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="label42.Size" type="System.Drawing.Size, System.Drawing">
+    <value>43, 13</value>
+  </data>
+  <data name="label42.Text" xml:space="preserve">
+    <value>方向舵</value>
+  </data>
+  <data name="label24.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>最大</value>
+  </data>
+  <data name="label40.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label40.Text" xml:space="preserve">
+    <value>最小</value>
+  </data>
+  <data name="label41.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label41.Text" xml:space="preserve">
+    <value>最低</value>
+  </data>
+  <data name="label21.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>最高</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>0度</value>
+  </data>
+  <data name="label39.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label39.Text" xml:space="preserve">
+    <value>微调</value>
+  </data>
+  <data name="label38.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label38.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="label37.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label37.Text" xml:space="preserve">
+    <value>位置</value>
+  </data>
+  <data name="label36.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label36.Text" xml:space="preserve">
+    <value>舵机</value>
+  </data>
+  <data name="label26.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>最大俯仰</value>
+  </data>
+  <data name="label25.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>最大侧倾</value>
+  </data>
+  <data name="label23.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>舵机行程</value>
+  </data>
+  <data name="label22.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>斜盘水平微调</value>
+  </data>
+  <data name="label17.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>斜盘舵机位置</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>重置</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>重置 APM 为默认设置</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APM设置</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.zh-TW.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.zh-TW.resx
new file mode 100644
index 0000000000000000000000000000000000000000..0c03fbf8ed6bd5befc34246175bf1adf106cce43
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.zh-TW.resx
@@ -0,0 +1,460 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>重置</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>遙控輸入</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>模式</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>硬件</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>電池</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>重置 APM 為默認設置</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch3.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch4.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch2.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch1.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>校準遙控</value>
+  </data>
+  <data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="label14.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>當前 PWM:</value>
+  </data>
+  <data name="label13.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>當前模式:</value>
+  </data>
+  <data name="label6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>飛行模式 6</value>
+  </data>
+  <data name="label5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>飛行模式 5</value>
+  </data>
+  <data name="label4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>飛行模式 4</value>
+  </data>
+  <data name="label3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>飛行模式 3</value>
+  </data>
+  <data name="label2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>飛行模式 2</value>
+  </data>
+  <data name="label1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>飛行模式 1</value>
+  </data>
+  <data name="BUT_SaveModes.Text" xml:space="preserve">
+    <value>保存模式</value>
+  </data>
+  <data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
+    <value>67, 13</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>磁偏角網站</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>磁偏角</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>啟用空速計</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>啟用聲納</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>啟用羅盤</value>
+  </data>
+  <data name="label35.Size" type="System.Drawing.Size, System.Drawing">
+    <value>63, 13</value>
+  </data>
+  <data name="label35.Text" xml:space="preserve">
+    <value>安培/伏特:</value>
+  </data>
+  <data name="label34.Size" type="System.Drawing.Size, System.Drawing">
+    <value>52, 13</value>
+  </data>
+  <data name="label34.Text" xml:space="preserve">
+    <value>分 壓 比:</value>
+  </data>
+  <data name="label33.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label33.Text" xml:space="preserve">
+    <value>電池電壓:</value>
+  </data>
+  <data name="label32.Size" type="System.Drawing.Size, System.Drawing">
+    <value>94, 13</value>
+  </data>
+  <data name="label32.Text" xml:space="preserve">
+    <value>測量的電池電壓:</value>
+  </data>
+  <data name="label31.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label31.Text" xml:space="preserve">
+    <value>輸入電壓:</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>電壓傳感器校準:
+1. 測量APM輸入電壓,輸入到下方的文本框中
+2. 測量電池電壓,輸入到下方的文本框中
+3. 從當前的傳感器的數據表中找到安培/伏特,輸入到下方的文本框中</value>
+  </data>
+  <data name="label29.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>容量</value>
+  </data>
+  <data name="label30.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 13</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>監控器</value>
+  </data>
+  <data name="label28.Size" type="System.Drawing.Size, System.Drawing">
+    <value>175, 13</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>設置水平面的默認加速度計偏移</value>
+  </data>
+  <data name="label16.Size" type="System.Drawing.Size, System.Drawing">
+    <value>261, 13</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>注: 圖片只是用於展示,設置可以用於六軸等機架</value>
+  </data>
+  <data name="label15.Size" type="System.Drawing.Size, System.Drawing">
+    <value>93, 13</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>機架設置 (+ 或 x)</value>
+  </data>
+  <data name="BUT_levelac2.Text" xml:space="preserve">
+    <value>找平</value>
+  </data>
+  <data name="label46.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label46.Text" xml:space="preserve">
+    <value>感度</value>
+  </data>
+  <data name="label45.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label45.Text" xml:space="preserve">
+    <value>啟用</value>
+  </data>
+  <data name="label44.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label44.Text" xml:space="preserve">
+    <value>微調</value>
+  </data>
+  <data name="label43.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label43.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="label42.Size" type="System.Drawing.Size, System.Drawing">
+    <value>43, 13</value>
+  </data>
+  <data name="label42.Text" xml:space="preserve">
+    <value>方向舵</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>手動</value>
+  </data>
+  <data name="label24.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>最大</value>
+  </data>
+  <data name="label40.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label40.Text" xml:space="preserve">
+    <value>最小</value>
+  </data>
+  <data name="BUT_swash_manual.Text" xml:space="preserve">
+    <value>手動</value>
+  </data>
+  <data name="label41.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label41.Text" xml:space="preserve">
+    <value>最低</value>
+  </data>
+  <data name="label21.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>最高</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>0度</value>
+  </data>
+  <data name="label39.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label39.Text" xml:space="preserve">
+    <value>微調</value>
+  </data>
+  <data name="label38.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label38.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="label37.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label37.Text" xml:space="preserve">
+    <value>位置</value>
+  </data>
+  <data name="label36.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label36.Text" xml:space="preserve">
+    <value>舵機</value>
+  </data>
+  <data name="label26.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>最大俯仰</value>
+  </data>
+  <data name="label25.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>最大側傾</value>
+  </data>
+  <data name="label23.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>舵機行程</value>
+  </data>
+  <data name="label22.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>斜盤水平微調</value>
+  </data>
+  <data name="label17.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>斜盤舵機位置</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APM設置</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs
new file mode 100644
index 0000000000000000000000000000000000000000..767aeb4a6f5906d525366944ad75cfe73e9cb280
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs
@@ -0,0 +1,1251 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    partial class ConfigArducopter
+    {
+        /// <summary> 
+        /// Required designer variable.
+        /// </summary>
+        private System.ComponentModel.IContainer components = null;
+
+        /// <summary> 
+        /// Clean up any resources being used.
+        /// </summary>
+        /// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
+        protected override void Dispose(bool disposing)
+        {
+            if (disposing && (components != null))
+            {
+                components.Dispose();
+            }
+            base.Dispose(disposing);
+        }
+
+        #region Component Designer generated code
+
+        /// <summary> 
+        /// Required method for Designer support - do not modify 
+        /// the contents of this method with the code editor.
+        /// </summary>
+        private void InitializeComponent()
+        {
+            this.components = new System.ComponentModel.Container();
+            this.myLabel3 = new ArdupilotMega.MyLabel();
+            this.TUNE_LOW = new System.Windows.Forms.NumericUpDown();
+            this.TUNE_HIGH = new System.Windows.Forms.NumericUpDown();
+            this.myLabel2 = new ArdupilotMega.MyLabel();
+            this.TUNE = new System.Windows.Forms.ComboBox();
+            this.myLabel1 = new ArdupilotMega.MyLabel();
+            this.CH7_OPT = new System.Windows.Forms.ComboBox();
+            this.groupBox5 = new System.Windows.Forms.GroupBox();
+            this.THR_RATE_D = new System.Windows.Forms.NumericUpDown();
+            this.label29 = new System.Windows.Forms.Label();
+            this.label14 = new System.Windows.Forms.Label();
+            this.THR_RATE_IMAX = new System.Windows.Forms.NumericUpDown();
+            this.THR_RATE_I = new System.Windows.Forms.NumericUpDown();
+            this.label20 = new System.Windows.Forms.Label();
+            this.THR_RATE_P = new System.Windows.Forms.NumericUpDown();
+            this.label25 = new System.Windows.Forms.Label();
+            this.CHK_lockrollpitch = new System.Windows.Forms.CheckBox();
+            this.groupBox4 = new System.Windows.Forms.GroupBox();
+            this.NAV_LAT_D = new System.Windows.Forms.NumericUpDown();
+            this.label27 = new System.Windows.Forms.Label();
+            this.WP_SPEED_MAX = new System.Windows.Forms.NumericUpDown();
+            this.label9 = new System.Windows.Forms.Label();
+            this.NAV_LAT_IMAX = new System.Windows.Forms.NumericUpDown();
+            this.label13 = new System.Windows.Forms.Label();
+            this.NAV_LAT_I = new System.Windows.Forms.NumericUpDown();
+            this.label15 = new System.Windows.Forms.Label();
+            this.NAV_LAT_P = new System.Windows.Forms.NumericUpDown();
+            this.label16 = new System.Windows.Forms.Label();
+            this.groupBox6 = new System.Windows.Forms.GroupBox();
+            this.XTRK_GAIN_SC1 = new System.Windows.Forms.NumericUpDown();
+            this.label18 = new System.Windows.Forms.Label();
+            this.groupBox7 = new System.Windows.Forms.GroupBox();
+            this.THR_ALT_IMAX = new System.Windows.Forms.NumericUpDown();
+            this.label19 = new System.Windows.Forms.Label();
+            this.THR_ALT_I = new System.Windows.Forms.NumericUpDown();
+            this.label21 = new System.Windows.Forms.Label();
+            this.THR_ALT_P = new System.Windows.Forms.NumericUpDown();
+            this.label22 = new System.Windows.Forms.Label();
+            this.groupBox19 = new System.Windows.Forms.GroupBox();
+            this.HLD_LAT_IMAX = new System.Windows.Forms.NumericUpDown();
+            this.label28 = new System.Windows.Forms.Label();
+            this.HLD_LAT_I = new System.Windows.Forms.NumericUpDown();
+            this.label30 = new System.Windows.Forms.Label();
+            this.HLD_LAT_P = new System.Windows.Forms.NumericUpDown();
+            this.label31 = new System.Windows.Forms.Label();
+            this.groupBox20 = new System.Windows.Forms.GroupBox();
+            this.STB_YAW_IMAX = new System.Windows.Forms.NumericUpDown();
+            this.label32 = new System.Windows.Forms.Label();
+            this.STB_YAW_I = new System.Windows.Forms.NumericUpDown();
+            this.label34 = new System.Windows.Forms.Label();
+            this.STB_YAW_P = new System.Windows.Forms.NumericUpDown();
+            this.label35 = new System.Windows.Forms.Label();
+            this.groupBox21 = new System.Windows.Forms.GroupBox();
+            this.STAB_D = new System.Windows.Forms.NumericUpDown();
+            this.lblSTAB_D = new System.Windows.Forms.Label();
+            this.STB_PIT_IMAX = new System.Windows.Forms.NumericUpDown();
+            this.label36 = new System.Windows.Forms.Label();
+            this.STB_PIT_I = new System.Windows.Forms.NumericUpDown();
+            this.label41 = new System.Windows.Forms.Label();
+            this.STB_PIT_P = new System.Windows.Forms.NumericUpDown();
+            this.label42 = new System.Windows.Forms.Label();
+            this.groupBox22 = new System.Windows.Forms.GroupBox();
+            this.STB_RLL_IMAX = new System.Windows.Forms.NumericUpDown();
+            this.label43 = new System.Windows.Forms.Label();
+            this.STB_RLL_I = new System.Windows.Forms.NumericUpDown();
+            this.label45 = new System.Windows.Forms.Label();
+            this.STB_RLL_P = new System.Windows.Forms.NumericUpDown();
+            this.label46 = new System.Windows.Forms.Label();
+            this.groupBox23 = new System.Windows.Forms.GroupBox();
+            this.RATE_YAW_D = new System.Windows.Forms.NumericUpDown();
+            this.label10 = new System.Windows.Forms.Label();
+            this.RATE_YAW_IMAX = new System.Windows.Forms.NumericUpDown();
+            this.label47 = new System.Windows.Forms.Label();
+            this.RATE_YAW_I = new System.Windows.Forms.NumericUpDown();
+            this.label77 = new System.Windows.Forms.Label();
+            this.RATE_YAW_P = new System.Windows.Forms.NumericUpDown();
+            this.label82 = new System.Windows.Forms.Label();
+            this.groupBox24 = new System.Windows.Forms.GroupBox();
+            this.RATE_PIT_D = new System.Windows.Forms.NumericUpDown();
+            this.label11 = new System.Windows.Forms.Label();
+            this.RATE_PIT_IMAX = new System.Windows.Forms.NumericUpDown();
+            this.label84 = new System.Windows.Forms.Label();
+            this.RATE_PIT_I = new System.Windows.Forms.NumericUpDown();
+            this.label86 = new System.Windows.Forms.Label();
+            this.RATE_PIT_P = new System.Windows.Forms.NumericUpDown();
+            this.label87 = new System.Windows.Forms.Label();
+            this.groupBox25 = new System.Windows.Forms.GroupBox();
+            this.RATE_RLL_D = new System.Windows.Forms.NumericUpDown();
+            this.label17 = new System.Windows.Forms.Label();
+            this.RATE_RLL_IMAX = new System.Windows.Forms.NumericUpDown();
+            this.label88 = new System.Windows.Forms.Label();
+            this.RATE_RLL_I = new System.Windows.Forms.NumericUpDown();
+            this.label90 = new System.Windows.Forms.Label();
+            this.RATE_RLL_P = new System.Windows.Forms.NumericUpDown();
+            this.label91 = new System.Windows.Forms.Label();
+            this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
+            ((System.ComponentModel.ISupportInitialize)(this.TUNE_LOW)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.TUNE_HIGH)).BeginInit();
+            this.groupBox5.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_D)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_IMAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_I)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_P)).BeginInit();
+            this.groupBox4.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_D)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.WP_SPEED_MAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_IMAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_I)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_P)).BeginInit();
+            this.groupBox6.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.XTRK_GAIN_SC1)).BeginInit();
+            this.groupBox7.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_IMAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_I)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_P)).BeginInit();
+            this.groupBox19.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_IMAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_I)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_P)).BeginInit();
+            this.groupBox20.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_IMAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_I)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_P)).BeginInit();
+            this.groupBox21.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.STAB_D)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_IMAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_I)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_P)).BeginInit();
+            this.groupBox22.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_IMAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_I)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_P)).BeginInit();
+            this.groupBox23.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_D)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_IMAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_I)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_P)).BeginInit();
+            this.groupBox24.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_D)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_IMAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_I)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_P)).BeginInit();
+            this.groupBox25.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_D)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_IMAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_I)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_P)).BeginInit();
+            this.SuspendLayout();
+            // 
+            // myLabel3
+            // 
+            this.myLabel3.Location = new System.Drawing.Point(540, 302);
+            this.myLabel3.Name = "myLabel3";
+            this.myLabel3.resize = false;
+            this.myLabel3.Size = new System.Drawing.Size(29, 23);
+            this.myLabel3.TabIndex = 42;
+            this.myLabel3.Text = "Min";
+            // 
+            // TUNE_LOW
+            // 
+            this.TUNE_LOW.Location = new System.Drawing.Point(575, 305);
+            this.TUNE_LOW.Name = "TUNE_LOW";
+            this.TUNE_LOW.Size = new System.Drawing.Size(51, 20);
+            this.TUNE_LOW.TabIndex = 41;
+            // 
+            // TUNE_HIGH
+            // 
+            this.TUNE_HIGH.Location = new System.Drawing.Point(665, 305);
+            this.TUNE_HIGH.Name = "TUNE_HIGH";
+            this.TUNE_HIGH.Size = new System.Drawing.Size(46, 20);
+            this.TUNE_HIGH.TabIndex = 40;
+            // 
+            // myLabel2
+            // 
+            this.myLabel2.Location = new System.Drawing.Point(540, 277);
+            this.myLabel2.Name = "myLabel2";
+            this.myLabel2.resize = false;
+            this.myLabel2.Size = new System.Drawing.Size(53, 23);
+            this.myLabel2.TabIndex = 39;
+            this.myLabel2.Text = "Ch6 Opt";
+            // 
+            // TUNE
+            // 
+            this.TUNE.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.TUNE.DropDownWidth = 150;
+            this.TUNE.FormattingEnabled = true;
+            this.TUNE.Items.AddRange(new object[] {
+            "CH6_NONE",
+            "CH6_STABILIZE_KP",
+            "CH6_STABILIZE_KI",
+            "CH6_YAW_KP",
+            "CH6_RATE_KP",
+            "CH6_RATE_KI",
+            "CH6_YAW_RATE_KP",
+            "CH6_THROTTLE_KP",
+            "CH6_TOP_BOTTOM_RATIO",
+            "CH6_RELAY",
+            "CH6_TRAVERSE_SPEED",
+            "CH6_NAV_P",
+            "CH6_LOITER_P",
+            "CH6_HELI_EXTERNAL_GYRO",
+            "CH6_THR_HOLD_KP",
+            "CH6_Z_GAIN",
+            "CH6_DAMP",
+            "CH6_OPTFLOW_KP",
+            "CH6_OPTFLOW_KI",
+            "CH6_OPTFLOW_KD",
+            "CH6_NAV_I",
+            "CH6_RATE_KD"});
+            this.TUNE.Location = new System.Drawing.Point(599, 277);
+            this.TUNE.Name = "TUNE";
+            this.TUNE.Size = new System.Drawing.Size(112, 21);
+            this.TUNE.TabIndex = 38;
+            // 
+            // myLabel1
+            // 
+            this.myLabel1.Location = new System.Drawing.Point(540, 329);
+            this.myLabel1.Name = "myLabel1";
+            this.myLabel1.resize = false;
+            this.myLabel1.Size = new System.Drawing.Size(53, 23);
+            this.myLabel1.TabIndex = 37;
+            this.myLabel1.Text = "Ch7 Opt";
+            // 
+            // CH7_OPT
+            // 
+            this.CH7_OPT.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CH7_OPT.DropDownWidth = 150;
+            this.CH7_OPT.FormattingEnabled = true;
+            this.CH7_OPT.Items.AddRange(new object[] {
+            "Do Nothing",
+            "",
+            "",
+            "Simple Mode",
+            "RTL",
+            "",
+            "",
+            "Save WP"});
+            this.CH7_OPT.Location = new System.Drawing.Point(599, 329);
+            this.CH7_OPT.Name = "CH7_OPT";
+            this.CH7_OPT.Size = new System.Drawing.Size(112, 21);
+            this.CH7_OPT.TabIndex = 36;
+            // 
+            // groupBox5
+            // 
+            this.groupBox5.Controls.Add(this.THR_RATE_D);
+            this.groupBox5.Controls.Add(this.label29);
+            this.groupBox5.Controls.Add(this.label14);
+            this.groupBox5.Controls.Add(this.THR_RATE_IMAX);
+            this.groupBox5.Controls.Add(this.THR_RATE_I);
+            this.groupBox5.Controls.Add(this.label20);
+            this.groupBox5.Controls.Add(this.THR_RATE_P);
+            this.groupBox5.Controls.Add(this.label25);
+            this.groupBox5.Location = new System.Drawing.Point(12, 267);
+            this.groupBox5.Name = "groupBox5";
+            this.groupBox5.Size = new System.Drawing.Size(170, 110);
+            this.groupBox5.TabIndex = 35;
+            this.groupBox5.TabStop = false;
+            this.groupBox5.Text = "Throttle Rate";
+            // 
+            // THR_RATE_D
+            // 
+            this.THR_RATE_D.Location = new System.Drawing.Point(80, 60);
+            this.THR_RATE_D.Name = "THR_RATE_D";
+            this.THR_RATE_D.Size = new System.Drawing.Size(78, 20);
+            this.THR_RATE_D.TabIndex = 14;
+            // 
+            // label29
+            // 
+            this.label29.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label29.Location = new System.Drawing.Point(6, 63);
+            this.label29.Name = "label29";
+            this.label29.Size = new System.Drawing.Size(10, 13);
+            this.label29.TabIndex = 15;
+            this.label29.Text = "D";
+            // 
+            // label14
+            // 
+            this.label14.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label14.Location = new System.Drawing.Point(6, 86);
+            this.label14.Name = "label14";
+            this.label14.Size = new System.Drawing.Size(65, 13);
+            this.label14.TabIndex = 16;
+            this.label14.Text = "IMAX";
+            // 
+            // THR_RATE_IMAX
+            // 
+            this.THR_RATE_IMAX.Location = new System.Drawing.Point(80, 83);
+            this.THR_RATE_IMAX.Name = "THR_RATE_IMAX";
+            this.THR_RATE_IMAX.Size = new System.Drawing.Size(78, 20);
+            this.THR_RATE_IMAX.TabIndex = 11;
+            // 
+            // THR_RATE_I
+            // 
+            this.THR_RATE_I.Location = new System.Drawing.Point(80, 37);
+            this.THR_RATE_I.Name = "THR_RATE_I";
+            this.THR_RATE_I.Size = new System.Drawing.Size(78, 20);
+            this.THR_RATE_I.TabIndex = 7;
+            // 
+            // label20
+            // 
+            this.label20.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label20.Location = new System.Drawing.Point(6, 40);
+            this.label20.Name = "label20";
+            this.label20.Size = new System.Drawing.Size(10, 13);
+            this.label20.TabIndex = 14;
+            this.label20.Text = "I";
+            // 
+            // THR_RATE_P
+            // 
+            this.THR_RATE_P.Location = new System.Drawing.Point(80, 13);
+            this.THR_RATE_P.Name = "THR_RATE_P";
+            this.THR_RATE_P.Size = new System.Drawing.Size(78, 20);
+            this.THR_RATE_P.TabIndex = 5;
+            // 
+            // label25
+            // 
+            this.label25.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label25.Location = new System.Drawing.Point(6, 16);
+            this.label25.Name = "label25";
+            this.label25.Size = new System.Drawing.Size(14, 13);
+            this.label25.TabIndex = 15;
+            this.label25.Text = "P";
+            // 
+            // CHK_lockrollpitch
+            // 
+            this.CHK_lockrollpitch.AutoSize = true;
+            this.CHK_lockrollpitch.Checked = true;
+            this.CHK_lockrollpitch.CheckState = System.Windows.Forms.CheckState.Checked;
+            this.CHK_lockrollpitch.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.CHK_lockrollpitch.Location = new System.Drawing.Point(9, 247);
+            this.CHK_lockrollpitch.Name = "CHK_lockrollpitch";
+            this.CHK_lockrollpitch.Size = new System.Drawing.Size(154, 17);
+            this.CHK_lockrollpitch.TabIndex = 34;
+            this.CHK_lockrollpitch.Text = "Lock Pitch and Roll Values";
+            this.CHK_lockrollpitch.UseVisualStyleBackColor = true;
+            // 
+            // groupBox4
+            // 
+            this.groupBox4.Controls.Add(this.NAV_LAT_D);
+            this.groupBox4.Controls.Add(this.label27);
+            this.groupBox4.Controls.Add(this.WP_SPEED_MAX);
+            this.groupBox4.Controls.Add(this.label9);
+            this.groupBox4.Controls.Add(this.NAV_LAT_IMAX);
+            this.groupBox4.Controls.Add(this.label13);
+            this.groupBox4.Controls.Add(this.NAV_LAT_I);
+            this.groupBox4.Controls.Add(this.label15);
+            this.groupBox4.Controls.Add(this.NAV_LAT_P);
+            this.groupBox4.Controls.Add(this.label16);
+            this.groupBox4.Location = new System.Drawing.Point(540, 133);
+            this.groupBox4.Name = "groupBox4";
+            this.groupBox4.Size = new System.Drawing.Size(170, 131);
+            this.groupBox4.TabIndex = 24;
+            this.groupBox4.TabStop = false;
+            this.groupBox4.Text = "Nav WP";
+            // 
+            // NAV_LAT_D
+            // 
+            this.NAV_LAT_D.Location = new System.Drawing.Point(80, 60);
+            this.NAV_LAT_D.Name = "NAV_LAT_D";
+            this.NAV_LAT_D.Size = new System.Drawing.Size(78, 20);
+            this.NAV_LAT_D.TabIndex = 18;
+            // 
+            // label27
+            // 
+            this.label27.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label27.Location = new System.Drawing.Point(6, 63);
+            this.label27.Name = "label27";
+            this.label27.Size = new System.Drawing.Size(10, 13);
+            this.label27.TabIndex = 19;
+            this.label27.Text = "D";
+            // 
+            // WP_SPEED_MAX
+            // 
+            this.WP_SPEED_MAX.Location = new System.Drawing.Point(80, 107);
+            this.WP_SPEED_MAX.Name = "WP_SPEED_MAX";
+            this.WP_SPEED_MAX.Size = new System.Drawing.Size(78, 20);
+            this.WP_SPEED_MAX.TabIndex = 16;
+            // 
+            // label9
+            // 
+            this.label9.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label9.Location = new System.Drawing.Point(6, 110);
+            this.label9.Name = "label9";
+            this.label9.Size = new System.Drawing.Size(54, 13);
+            this.label9.TabIndex = 17;
+            this.label9.Text = "m/s";
+            // 
+            // NAV_LAT_IMAX
+            // 
+            this.NAV_LAT_IMAX.Location = new System.Drawing.Point(80, 84);
+            this.NAV_LAT_IMAX.Name = "NAV_LAT_IMAX";
+            this.NAV_LAT_IMAX.Size = new System.Drawing.Size(78, 20);
+            this.NAV_LAT_IMAX.TabIndex = 11;
+            // 
+            // label13
+            // 
+            this.label13.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label13.Location = new System.Drawing.Point(6, 87);
+            this.label13.Name = "label13";
+            this.label13.Size = new System.Drawing.Size(65, 13);
+            this.label13.TabIndex = 12;
+            this.label13.Text = "IMAX";
+            // 
+            // NAV_LAT_I
+            // 
+            this.NAV_LAT_I.Location = new System.Drawing.Point(80, 37);
+            this.NAV_LAT_I.Name = "NAV_LAT_I";
+            this.NAV_LAT_I.Size = new System.Drawing.Size(78, 20);
+            this.NAV_LAT_I.TabIndex = 7;
+            // 
+            // label15
+            // 
+            this.label15.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label15.Location = new System.Drawing.Point(6, 40);
+            this.label15.Name = "label15";
+            this.label15.Size = new System.Drawing.Size(10, 13);
+            this.label15.TabIndex = 14;
+            this.label15.Text = "I";
+            // 
+            // NAV_LAT_P
+            // 
+            this.NAV_LAT_P.Location = new System.Drawing.Point(80, 13);
+            this.NAV_LAT_P.Name = "NAV_LAT_P";
+            this.NAV_LAT_P.Size = new System.Drawing.Size(78, 20);
+            this.NAV_LAT_P.TabIndex = 5;
+            // 
+            // label16
+            // 
+            this.label16.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label16.Location = new System.Drawing.Point(6, 16);
+            this.label16.Name = "label16";
+            this.label16.Size = new System.Drawing.Size(14, 13);
+            this.label16.TabIndex = 15;
+            this.label16.Text = "P";
+            // 
+            // groupBox6
+            // 
+            this.groupBox6.Controls.Add(this.XTRK_GAIN_SC1);
+            this.groupBox6.Controls.Add(this.label18);
+            this.groupBox6.Location = new System.Drawing.Point(364, 267);
+            this.groupBox6.Name = "groupBox6";
+            this.groupBox6.Size = new System.Drawing.Size(170, 43);
+            this.groupBox6.TabIndex = 25;
+            this.groupBox6.TabStop = false;
+            this.groupBox6.Text = "Crosstrack Correction";
+            // 
+            // XTRK_GAIN_SC1
+            // 
+            this.XTRK_GAIN_SC1.Location = new System.Drawing.Point(80, 13);
+            this.XTRK_GAIN_SC1.Name = "XTRK_GAIN_SC1";
+            this.XTRK_GAIN_SC1.Size = new System.Drawing.Size(78, 20);
+            this.XTRK_GAIN_SC1.TabIndex = 5;
+            // 
+            // label18
+            // 
+            this.label18.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label18.Location = new System.Drawing.Point(6, 16);
+            this.label18.Name = "label18";
+            this.label18.Size = new System.Drawing.Size(38, 13);
+            this.label18.TabIndex = 15;
+            this.label18.Text = "Gain";
+            // 
+            // groupBox7
+            // 
+            this.groupBox7.Controls.Add(this.THR_ALT_IMAX);
+            this.groupBox7.Controls.Add(this.label19);
+            this.groupBox7.Controls.Add(this.THR_ALT_I);
+            this.groupBox7.Controls.Add(this.label21);
+            this.groupBox7.Controls.Add(this.THR_ALT_P);
+            this.groupBox7.Controls.Add(this.label22);
+            this.groupBox7.Location = new System.Drawing.Point(188, 267);
+            this.groupBox7.Name = "groupBox7";
+            this.groupBox7.Size = new System.Drawing.Size(170, 110);
+            this.groupBox7.TabIndex = 26;
+            this.groupBox7.TabStop = false;
+            this.groupBox7.Text = "Altitude Hold";
+            // 
+            // THR_ALT_IMAX
+            // 
+            this.THR_ALT_IMAX.Location = new System.Drawing.Point(80, 63);
+            this.THR_ALT_IMAX.Name = "THR_ALT_IMAX";
+            this.THR_ALT_IMAX.Size = new System.Drawing.Size(78, 20);
+            this.THR_ALT_IMAX.TabIndex = 11;
+            // 
+            // label19
+            // 
+            this.label19.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label19.Location = new System.Drawing.Point(6, 66);
+            this.label19.Name = "label19";
+            this.label19.Size = new System.Drawing.Size(65, 13);
+            this.label19.TabIndex = 12;
+            this.label19.Text = "IMAX";
+            // 
+            // THR_ALT_I
+            // 
+            this.THR_ALT_I.Location = new System.Drawing.Point(80, 37);
+            this.THR_ALT_I.Name = "THR_ALT_I";
+            this.THR_ALT_I.Size = new System.Drawing.Size(78, 20);
+            this.THR_ALT_I.TabIndex = 7;
+            // 
+            // label21
+            // 
+            this.label21.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label21.Location = new System.Drawing.Point(6, 40);
+            this.label21.Name = "label21";
+            this.label21.Size = new System.Drawing.Size(10, 13);
+            this.label21.TabIndex = 14;
+            this.label21.Text = "I";
+            // 
+            // THR_ALT_P
+            // 
+            this.THR_ALT_P.Location = new System.Drawing.Point(80, 13);
+            this.THR_ALT_P.Name = "THR_ALT_P";
+            this.THR_ALT_P.Size = new System.Drawing.Size(78, 20);
+            this.THR_ALT_P.TabIndex = 5;
+            // 
+            // label22
+            // 
+            this.label22.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label22.Location = new System.Drawing.Point(6, 16);
+            this.label22.Name = "label22";
+            this.label22.Size = new System.Drawing.Size(14, 13);
+            this.label22.TabIndex = 15;
+            this.label22.Text = "P";
+            // 
+            // groupBox19
+            // 
+            this.groupBox19.Controls.Add(this.HLD_LAT_IMAX);
+            this.groupBox19.Controls.Add(this.label28);
+            this.groupBox19.Controls.Add(this.HLD_LAT_I);
+            this.groupBox19.Controls.Add(this.label30);
+            this.groupBox19.Controls.Add(this.HLD_LAT_P);
+            this.groupBox19.Controls.Add(this.label31);
+            this.groupBox19.Location = new System.Drawing.Point(537, 13);
+            this.groupBox19.Name = "groupBox19";
+            this.groupBox19.Size = new System.Drawing.Size(170, 95);
+            this.groupBox19.TabIndex = 27;
+            this.groupBox19.TabStop = false;
+            this.groupBox19.Text = "Loiter";
+            // 
+            // HLD_LAT_IMAX
+            // 
+            this.HLD_LAT_IMAX.Location = new System.Drawing.Point(80, 61);
+            this.HLD_LAT_IMAX.Name = "HLD_LAT_IMAX";
+            this.HLD_LAT_IMAX.Size = new System.Drawing.Size(78, 20);
+            this.HLD_LAT_IMAX.TabIndex = 11;
+            // 
+            // label28
+            // 
+            this.label28.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label28.Location = new System.Drawing.Point(6, 64);
+            this.label28.Name = "label28";
+            this.label28.Size = new System.Drawing.Size(65, 13);
+            this.label28.TabIndex = 12;
+            this.label28.Text = "IMAX";
+            // 
+            // HLD_LAT_I
+            // 
+            this.HLD_LAT_I.Location = new System.Drawing.Point(80, 37);
+            this.HLD_LAT_I.Name = "HLD_LAT_I";
+            this.HLD_LAT_I.Size = new System.Drawing.Size(78, 20);
+            this.HLD_LAT_I.TabIndex = 7;
+            // 
+            // label30
+            // 
+            this.label30.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label30.Location = new System.Drawing.Point(6, 40);
+            this.label30.Name = "label30";
+            this.label30.Size = new System.Drawing.Size(10, 13);
+            this.label30.TabIndex = 14;
+            this.label30.Text = "I";
+            // 
+            // HLD_LAT_P
+            // 
+            this.HLD_LAT_P.Location = new System.Drawing.Point(80, 13);
+            this.HLD_LAT_P.Name = "HLD_LAT_P";
+            this.HLD_LAT_P.Size = new System.Drawing.Size(78, 20);
+            this.HLD_LAT_P.TabIndex = 5;
+            // 
+            // label31
+            // 
+            this.label31.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label31.Location = new System.Drawing.Point(6, 16);
+            this.label31.Name = "label31";
+            this.label31.Size = new System.Drawing.Size(14, 13);
+            this.label31.TabIndex = 15;
+            this.label31.Text = "P";
+            // 
+            // groupBox20
+            // 
+            this.groupBox20.Controls.Add(this.STB_YAW_IMAX);
+            this.groupBox20.Controls.Add(this.label32);
+            this.groupBox20.Controls.Add(this.STB_YAW_I);
+            this.groupBox20.Controls.Add(this.label34);
+            this.groupBox20.Controls.Add(this.STB_YAW_P);
+            this.groupBox20.Controls.Add(this.label35);
+            this.groupBox20.Location = new System.Drawing.Point(364, 13);
+            this.groupBox20.Name = "groupBox20";
+            this.groupBox20.Size = new System.Drawing.Size(170, 95);
+            this.groupBox20.TabIndex = 28;
+            this.groupBox20.TabStop = false;
+            this.groupBox20.Text = "Stabilize Yaw";
+            // 
+            // STB_YAW_IMAX
+            // 
+            this.STB_YAW_IMAX.Location = new System.Drawing.Point(80, 63);
+            this.STB_YAW_IMAX.Name = "STB_YAW_IMAX";
+            this.STB_YAW_IMAX.Size = new System.Drawing.Size(78, 20);
+            this.STB_YAW_IMAX.TabIndex = 11;
+            // 
+            // label32
+            // 
+            this.label32.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label32.Location = new System.Drawing.Point(6, 66);
+            this.label32.Name = "label32";
+            this.label32.Size = new System.Drawing.Size(65, 13);
+            this.label32.TabIndex = 12;
+            this.label32.Text = "IMAX ";
+            // 
+            // STB_YAW_I
+            // 
+            this.STB_YAW_I.Location = new System.Drawing.Point(80, 37);
+            this.STB_YAW_I.Name = "STB_YAW_I";
+            this.STB_YAW_I.Size = new System.Drawing.Size(78, 20);
+            this.STB_YAW_I.TabIndex = 7;
+            // 
+            // label34
+            // 
+            this.label34.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label34.Location = new System.Drawing.Point(6, 40);
+            this.label34.Name = "label34";
+            this.label34.Size = new System.Drawing.Size(10, 13);
+            this.label34.TabIndex = 14;
+            this.label34.Text = "I";
+            // 
+            // STB_YAW_P
+            // 
+            this.STB_YAW_P.Location = new System.Drawing.Point(80, 13);
+            this.STB_YAW_P.Name = "STB_YAW_P";
+            this.STB_YAW_P.Size = new System.Drawing.Size(78, 20);
+            this.STB_YAW_P.TabIndex = 5;
+            // 
+            // label35
+            // 
+            this.label35.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label35.Location = new System.Drawing.Point(6, 16);
+            this.label35.Name = "label35";
+            this.label35.Size = new System.Drawing.Size(14, 13);
+            this.label35.TabIndex = 15;
+            this.label35.Text = "P";
+            // 
+            // groupBox21
+            // 
+            this.groupBox21.Controls.Add(this.STAB_D);
+            this.groupBox21.Controls.Add(this.lblSTAB_D);
+            this.groupBox21.Controls.Add(this.STB_PIT_IMAX);
+            this.groupBox21.Controls.Add(this.label36);
+            this.groupBox21.Controls.Add(this.STB_PIT_I);
+            this.groupBox21.Controls.Add(this.label41);
+            this.groupBox21.Controls.Add(this.STB_PIT_P);
+            this.groupBox21.Controls.Add(this.label42);
+            this.groupBox21.Location = new System.Drawing.Point(188, 13);
+            this.groupBox21.Name = "groupBox21";
+            this.groupBox21.Size = new System.Drawing.Size(170, 114);
+            this.groupBox21.TabIndex = 29;
+            this.groupBox21.TabStop = false;
+            this.groupBox21.Text = "Stabilize Pitch";
+            // 
+            // STAB_D
+            // 
+            this.STAB_D.Location = new System.Drawing.Point(80, 88);
+            this.STAB_D.Name = "STAB_D";
+            this.STAB_D.Size = new System.Drawing.Size(78, 20);
+            this.STAB_D.TabIndex = 16;
+            // 
+            // lblSTAB_D
+            // 
+            this.lblSTAB_D.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.lblSTAB_D.Location = new System.Drawing.Point(6, 91);
+            this.lblSTAB_D.Name = "lblSTAB_D";
+            this.lblSTAB_D.Size = new System.Drawing.Size(65, 13);
+            this.lblSTAB_D.TabIndex = 17;
+            this.lblSTAB_D.Text = "Stabilize D";
+            // 
+            // STB_PIT_IMAX
+            // 
+            this.STB_PIT_IMAX.Location = new System.Drawing.Point(80, 63);
+            this.STB_PIT_IMAX.Name = "STB_PIT_IMAX";
+            this.STB_PIT_IMAX.Size = new System.Drawing.Size(78, 20);
+            this.STB_PIT_IMAX.TabIndex = 11;
+            // 
+            // label36
+            // 
+            this.label36.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label36.Location = new System.Drawing.Point(6, 66);
+            this.label36.Name = "label36";
+            this.label36.Size = new System.Drawing.Size(65, 13);
+            this.label36.TabIndex = 12;
+            this.label36.Text = "IMAX";
+            // 
+            // STB_PIT_I
+            // 
+            this.STB_PIT_I.Location = new System.Drawing.Point(80, 37);
+            this.STB_PIT_I.Name = "STB_PIT_I";
+            this.STB_PIT_I.Size = new System.Drawing.Size(78, 20);
+            this.STB_PIT_I.TabIndex = 7;
+            // 
+            // label41
+            // 
+            this.label41.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label41.Location = new System.Drawing.Point(6, 40);
+            this.label41.Name = "label41";
+            this.label41.Size = new System.Drawing.Size(10, 13);
+            this.label41.TabIndex = 14;
+            this.label41.Text = "I";
+            // 
+            // STB_PIT_P
+            // 
+            this.STB_PIT_P.Location = new System.Drawing.Point(80, 13);
+            this.STB_PIT_P.Name = "STB_PIT_P";
+            this.STB_PIT_P.Size = new System.Drawing.Size(78, 20);
+            this.STB_PIT_P.TabIndex = 5;
+            // 
+            // label42
+            // 
+            this.label42.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label42.Location = new System.Drawing.Point(6, 16);
+            this.label42.Name = "label42";
+            this.label42.Size = new System.Drawing.Size(14, 13);
+            this.label42.TabIndex = 15;
+            this.label42.Text = "P";
+            // 
+            // groupBox22
+            // 
+            this.groupBox22.Controls.Add(this.STB_RLL_IMAX);
+            this.groupBox22.Controls.Add(this.label43);
+            this.groupBox22.Controls.Add(this.STB_RLL_I);
+            this.groupBox22.Controls.Add(this.label45);
+            this.groupBox22.Controls.Add(this.STB_RLL_P);
+            this.groupBox22.Controls.Add(this.label46);
+            this.groupBox22.Location = new System.Drawing.Point(12, 13);
+            this.groupBox22.Name = "groupBox22";
+            this.groupBox22.Size = new System.Drawing.Size(170, 95);
+            this.groupBox22.TabIndex = 30;
+            this.groupBox22.TabStop = false;
+            this.groupBox22.Text = "Stabilize Roll";
+            // 
+            // STB_RLL_IMAX
+            // 
+            this.STB_RLL_IMAX.Location = new System.Drawing.Point(80, 63);
+            this.STB_RLL_IMAX.Name = "STB_RLL_IMAX";
+            this.STB_RLL_IMAX.Size = new System.Drawing.Size(78, 20);
+            this.STB_RLL_IMAX.TabIndex = 11;
+            // 
+            // label43
+            // 
+            this.label43.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label43.Location = new System.Drawing.Point(6, 66);
+            this.label43.Name = "label43";
+            this.label43.Size = new System.Drawing.Size(65, 13);
+            this.label43.TabIndex = 12;
+            this.label43.Text = "IMAX";
+            // 
+            // STB_RLL_I
+            // 
+            this.STB_RLL_I.Location = new System.Drawing.Point(80, 37);
+            this.STB_RLL_I.Name = "STB_RLL_I";
+            this.STB_RLL_I.Size = new System.Drawing.Size(78, 20);
+            this.STB_RLL_I.TabIndex = 7;
+            // 
+            // label45
+            // 
+            this.label45.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label45.Location = new System.Drawing.Point(6, 40);
+            this.label45.Name = "label45";
+            this.label45.Size = new System.Drawing.Size(10, 13);
+            this.label45.TabIndex = 14;
+            this.label45.Text = "I";
+            // 
+            // STB_RLL_P
+            // 
+            this.STB_RLL_P.Location = new System.Drawing.Point(80, 13);
+            this.STB_RLL_P.Name = "STB_RLL_P";
+            this.STB_RLL_P.Size = new System.Drawing.Size(78, 20);
+            this.STB_RLL_P.TabIndex = 5;
+            // 
+            // label46
+            // 
+            this.label46.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label46.Location = new System.Drawing.Point(6, 16);
+            this.label46.Name = "label46";
+            this.label46.Size = new System.Drawing.Size(14, 13);
+            this.label46.TabIndex = 15;
+            this.label46.Text = "P";
+            // 
+            // groupBox23
+            // 
+            this.groupBox23.Controls.Add(this.RATE_YAW_D);
+            this.groupBox23.Controls.Add(this.label10);
+            this.groupBox23.Controls.Add(this.RATE_YAW_IMAX);
+            this.groupBox23.Controls.Add(this.label47);
+            this.groupBox23.Controls.Add(this.RATE_YAW_I);
+            this.groupBox23.Controls.Add(this.label77);
+            this.groupBox23.Controls.Add(this.RATE_YAW_P);
+            this.groupBox23.Controls.Add(this.label82);
+            this.groupBox23.Location = new System.Drawing.Point(364, 133);
+            this.groupBox23.Name = "groupBox23";
+            this.groupBox23.Size = new System.Drawing.Size(170, 108);
+            this.groupBox23.TabIndex = 31;
+            this.groupBox23.TabStop = false;
+            this.groupBox23.Text = "Rate Yaw";
+            // 
+            // RATE_YAW_D
+            // 
+            this.RATE_YAW_D.Location = new System.Drawing.Point(80, 60);
+            this.RATE_YAW_D.Name = "RATE_YAW_D";
+            this.RATE_YAW_D.Size = new System.Drawing.Size(78, 20);
+            this.RATE_YAW_D.TabIndex = 8;
+            // 
+            // label10
+            // 
+            this.label10.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label10.Location = new System.Drawing.Point(6, 63);
+            this.label10.Name = "label10";
+            this.label10.Size = new System.Drawing.Size(10, 13);
+            this.label10.TabIndex = 9;
+            this.label10.Text = "D";
+            // 
+            // RATE_YAW_IMAX
+            // 
+            this.RATE_YAW_IMAX.Location = new System.Drawing.Point(80, 84);
+            this.RATE_YAW_IMAX.Name = "RATE_YAW_IMAX";
+            this.RATE_YAW_IMAX.Size = new System.Drawing.Size(78, 20);
+            this.RATE_YAW_IMAX.TabIndex = 0;
+            // 
+            // label47
+            // 
+            this.label47.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label47.Location = new System.Drawing.Point(6, 87);
+            this.label47.Name = "label47";
+            this.label47.Size = new System.Drawing.Size(65, 13);
+            this.label47.TabIndex = 1;
+            this.label47.Text = "IMAX";
+            // 
+            // RATE_YAW_I
+            // 
+            this.RATE_YAW_I.Location = new System.Drawing.Point(80, 37);
+            this.RATE_YAW_I.Name = "RATE_YAW_I";
+            this.RATE_YAW_I.Size = new System.Drawing.Size(78, 20);
+            this.RATE_YAW_I.TabIndex = 4;
+            // 
+            // label77
+            // 
+            this.label77.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label77.Location = new System.Drawing.Point(6, 40);
+            this.label77.Name = "label77";
+            this.label77.Size = new System.Drawing.Size(10, 13);
+            this.label77.TabIndex = 5;
+            this.label77.Text = "I";
+            // 
+            // RATE_YAW_P
+            // 
+            this.RATE_YAW_P.Location = new System.Drawing.Point(80, 13);
+            this.RATE_YAW_P.Name = "RATE_YAW_P";
+            this.RATE_YAW_P.Size = new System.Drawing.Size(78, 20);
+            this.RATE_YAW_P.TabIndex = 6;
+            // 
+            // label82
+            // 
+            this.label82.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label82.Location = new System.Drawing.Point(6, 16);
+            this.label82.Name = "label82";
+            this.label82.Size = new System.Drawing.Size(14, 13);
+            this.label82.TabIndex = 7;
+            this.label82.Text = "P";
+            // 
+            // groupBox24
+            // 
+            this.groupBox24.Controls.Add(this.RATE_PIT_D);
+            this.groupBox24.Controls.Add(this.label11);
+            this.groupBox24.Controls.Add(this.RATE_PIT_IMAX);
+            this.groupBox24.Controls.Add(this.label84);
+            this.groupBox24.Controls.Add(this.RATE_PIT_I);
+            this.groupBox24.Controls.Add(this.label86);
+            this.groupBox24.Controls.Add(this.RATE_PIT_P);
+            this.groupBox24.Controls.Add(this.label87);
+            this.groupBox24.Location = new System.Drawing.Point(188, 133);
+            this.groupBox24.Name = "groupBox24";
+            this.groupBox24.Size = new System.Drawing.Size(170, 108);
+            this.groupBox24.TabIndex = 32;
+            this.groupBox24.TabStop = false;
+            this.groupBox24.Text = "Rate Pitch";
+            // 
+            // RATE_PIT_D
+            // 
+            this.RATE_PIT_D.Location = new System.Drawing.Point(80, 60);
+            this.RATE_PIT_D.Name = "RATE_PIT_D";
+            this.RATE_PIT_D.Size = new System.Drawing.Size(78, 20);
+            this.RATE_PIT_D.TabIndex = 10;
+            // 
+            // label11
+            // 
+            this.label11.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label11.Location = new System.Drawing.Point(6, 63);
+            this.label11.Name = "label11";
+            this.label11.Size = new System.Drawing.Size(10, 13);
+            this.label11.TabIndex = 11;
+            this.label11.Text = "D";
+            // 
+            // RATE_PIT_IMAX
+            // 
+            this.RATE_PIT_IMAX.Location = new System.Drawing.Point(80, 83);
+            this.RATE_PIT_IMAX.Name = "RATE_PIT_IMAX";
+            this.RATE_PIT_IMAX.Size = new System.Drawing.Size(78, 20);
+            this.RATE_PIT_IMAX.TabIndex = 0;
+            // 
+            // label84
+            // 
+            this.label84.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label84.Location = new System.Drawing.Point(6, 86);
+            this.label84.Name = "label84";
+            this.label84.Size = new System.Drawing.Size(65, 13);
+            this.label84.TabIndex = 1;
+            this.label84.Text = "IMAX";
+            // 
+            // RATE_PIT_I
+            // 
+            this.RATE_PIT_I.Location = new System.Drawing.Point(80, 37);
+            this.RATE_PIT_I.Name = "RATE_PIT_I";
+            this.RATE_PIT_I.Size = new System.Drawing.Size(78, 20);
+            this.RATE_PIT_I.TabIndex = 4;
+            // 
+            // label86
+            // 
+            this.label86.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label86.Location = new System.Drawing.Point(6, 40);
+            this.label86.Name = "label86";
+            this.label86.Size = new System.Drawing.Size(10, 13);
+            this.label86.TabIndex = 5;
+            this.label86.Text = "I";
+            // 
+            // RATE_PIT_P
+            // 
+            this.RATE_PIT_P.Location = new System.Drawing.Point(80, 13);
+            this.RATE_PIT_P.Name = "RATE_PIT_P";
+            this.RATE_PIT_P.Size = new System.Drawing.Size(78, 20);
+            this.RATE_PIT_P.TabIndex = 6;
+            // 
+            // label87
+            // 
+            this.label87.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label87.Location = new System.Drawing.Point(6, 16);
+            this.label87.Name = "label87";
+            this.label87.Size = new System.Drawing.Size(14, 13);
+            this.label87.TabIndex = 7;
+            this.label87.Text = "P";
+            // 
+            // groupBox25
+            // 
+            this.groupBox25.Controls.Add(this.RATE_RLL_D);
+            this.groupBox25.Controls.Add(this.label17);
+            this.groupBox25.Controls.Add(this.RATE_RLL_IMAX);
+            this.groupBox25.Controls.Add(this.label88);
+            this.groupBox25.Controls.Add(this.RATE_RLL_I);
+            this.groupBox25.Controls.Add(this.label90);
+            this.groupBox25.Controls.Add(this.RATE_RLL_P);
+            this.groupBox25.Controls.Add(this.label91);
+            this.groupBox25.Location = new System.Drawing.Point(12, 133);
+            this.groupBox25.Name = "groupBox25";
+            this.groupBox25.Size = new System.Drawing.Size(170, 108);
+            this.groupBox25.TabIndex = 33;
+            this.groupBox25.TabStop = false;
+            this.groupBox25.Text = "Rate Roll";
+            // 
+            // RATE_RLL_D
+            // 
+            this.RATE_RLL_D.Location = new System.Drawing.Point(80, 60);
+            this.RATE_RLL_D.Name = "RATE_RLL_D";
+            this.RATE_RLL_D.Size = new System.Drawing.Size(78, 20);
+            this.RATE_RLL_D.TabIndex = 12;
+            // 
+            // label17
+            // 
+            this.label17.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label17.Location = new System.Drawing.Point(6, 63);
+            this.label17.Name = "label17";
+            this.label17.Size = new System.Drawing.Size(10, 13);
+            this.label17.TabIndex = 13;
+            this.label17.Text = "D";
+            // 
+            // RATE_RLL_IMAX
+            // 
+            this.RATE_RLL_IMAX.Location = new System.Drawing.Point(80, 83);
+            this.RATE_RLL_IMAX.Name = "RATE_RLL_IMAX";
+            this.RATE_RLL_IMAX.Size = new System.Drawing.Size(78, 20);
+            this.RATE_RLL_IMAX.TabIndex = 0;
+            // 
+            // label88
+            // 
+            this.label88.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label88.Location = new System.Drawing.Point(6, 86);
+            this.label88.Name = "label88";
+            this.label88.Size = new System.Drawing.Size(68, 13);
+            this.label88.TabIndex = 1;
+            this.label88.Text = "IMAX";
+            // 
+            // RATE_RLL_I
+            // 
+            this.RATE_RLL_I.Location = new System.Drawing.Point(80, 37);
+            this.RATE_RLL_I.Name = "RATE_RLL_I";
+            this.RATE_RLL_I.Size = new System.Drawing.Size(78, 20);
+            this.RATE_RLL_I.TabIndex = 4;
+            // 
+            // label90
+            // 
+            this.label90.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label90.Location = new System.Drawing.Point(6, 40);
+            this.label90.Name = "label90";
+            this.label90.Size = new System.Drawing.Size(10, 13);
+            this.label90.TabIndex = 5;
+            this.label90.Text = "I";
+            // 
+            // RATE_RLL_P
+            // 
+            this.RATE_RLL_P.Location = new System.Drawing.Point(80, 13);
+            this.RATE_RLL_P.Name = "RATE_RLL_P";
+            this.RATE_RLL_P.Size = new System.Drawing.Size(78, 20);
+            this.RATE_RLL_P.TabIndex = 6;
+            // 
+            // label91
+            // 
+            this.label91.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label91.Location = new System.Drawing.Point(6, 16);
+            this.label91.Name = "label91";
+            this.label91.Size = new System.Drawing.Size(14, 13);
+            this.label91.TabIndex = 7;
+            this.label91.Text = "P";
+            // 
+            // ConfigArducopter
+            // 
+            this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
+            this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+            this.Controls.Add(this.myLabel3);
+            this.Controls.Add(this.TUNE_LOW);
+            this.Controls.Add(this.TUNE_HIGH);
+            this.Controls.Add(this.myLabel2);
+            this.Controls.Add(this.TUNE);
+            this.Controls.Add(this.myLabel1);
+            this.Controls.Add(this.CH7_OPT);
+            this.Controls.Add(this.groupBox5);
+            this.Controls.Add(this.CHK_lockrollpitch);
+            this.Controls.Add(this.groupBox4);
+            this.Controls.Add(this.groupBox6);
+            this.Controls.Add(this.groupBox7);
+            this.Controls.Add(this.groupBox19);
+            this.Controls.Add(this.groupBox20);
+            this.Controls.Add(this.groupBox21);
+            this.Controls.Add(this.groupBox22);
+            this.Controls.Add(this.groupBox23);
+            this.Controls.Add(this.groupBox24);
+            this.Controls.Add(this.groupBox25);
+            this.Name = "ConfigArducopter";
+            this.Size = new System.Drawing.Size(728, 393);
+            this.Load += new System.EventHandler(this.ConfigArducopter_Load);
+            ((System.ComponentModel.ISupportInitialize)(this.TUNE_LOW)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.TUNE_HIGH)).EndInit();
+            this.groupBox5.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_D)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_IMAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_I)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.THR_RATE_P)).EndInit();
+            this.groupBox4.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_D)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.WP_SPEED_MAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_IMAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_I)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.NAV_LAT_P)).EndInit();
+            this.groupBox6.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.XTRK_GAIN_SC1)).EndInit();
+            this.groupBox7.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_IMAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_I)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.THR_ALT_P)).EndInit();
+            this.groupBox19.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_IMAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_I)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.HLD_LAT_P)).EndInit();
+            this.groupBox20.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_IMAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_I)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.STB_YAW_P)).EndInit();
+            this.groupBox21.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.STAB_D)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_IMAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_I)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.STB_PIT_P)).EndInit();
+            this.groupBox22.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_IMAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_I)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.STB_RLL_P)).EndInit();
+            this.groupBox23.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_D)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_IMAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_I)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_YAW_P)).EndInit();
+            this.groupBox24.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_D)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_IMAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_I)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_PIT_P)).EndInit();
+            this.groupBox25.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_D)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_IMAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_I)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RATE_RLL_P)).EndInit();
+            this.ResumeLayout(false);
+            this.PerformLayout();
+
+        }
+
+        #endregion
+
+        private MyLabel myLabel3;
+        private System.Windows.Forms.NumericUpDown TUNE_LOW;
+        private System.Windows.Forms.NumericUpDown TUNE_HIGH;
+        private MyLabel myLabel2;
+        private System.Windows.Forms.ComboBox TUNE;
+        private MyLabel myLabel1;
+        private System.Windows.Forms.ComboBox CH7_OPT;
+        private System.Windows.Forms.GroupBox groupBox5;
+        private System.Windows.Forms.NumericUpDown THR_RATE_D;
+        private System.Windows.Forms.Label label29;
+        private System.Windows.Forms.Label label14;
+        private System.Windows.Forms.NumericUpDown THR_RATE_IMAX;
+        private System.Windows.Forms.NumericUpDown THR_RATE_I;
+        private System.Windows.Forms.Label label20;
+        private System.Windows.Forms.NumericUpDown THR_RATE_P;
+        private System.Windows.Forms.Label label25;
+        private System.Windows.Forms.CheckBox CHK_lockrollpitch;
+        private System.Windows.Forms.GroupBox groupBox4;
+        private System.Windows.Forms.NumericUpDown NAV_LAT_D;
+        private System.Windows.Forms.Label label27;
+        private System.Windows.Forms.NumericUpDown WP_SPEED_MAX;
+        private System.Windows.Forms.Label label9;
+        private System.Windows.Forms.NumericUpDown NAV_LAT_IMAX;
+        private System.Windows.Forms.Label label13;
+        private System.Windows.Forms.NumericUpDown NAV_LAT_I;
+        private System.Windows.Forms.Label label15;
+        private System.Windows.Forms.NumericUpDown NAV_LAT_P;
+        private System.Windows.Forms.Label label16;
+        private System.Windows.Forms.GroupBox groupBox6;
+        private System.Windows.Forms.NumericUpDown XTRK_GAIN_SC1;
+        private System.Windows.Forms.Label label18;
+        private System.Windows.Forms.GroupBox groupBox7;
+        private System.Windows.Forms.NumericUpDown THR_ALT_IMAX;
+        private System.Windows.Forms.Label label19;
+        private System.Windows.Forms.NumericUpDown THR_ALT_I;
+        private System.Windows.Forms.Label label21;
+        private System.Windows.Forms.NumericUpDown THR_ALT_P;
+        private System.Windows.Forms.Label label22;
+        private System.Windows.Forms.GroupBox groupBox19;
+        private System.Windows.Forms.NumericUpDown HLD_LAT_IMAX;
+        private System.Windows.Forms.Label label28;
+        private System.Windows.Forms.NumericUpDown HLD_LAT_I;
+        private System.Windows.Forms.Label label30;
+        private System.Windows.Forms.NumericUpDown HLD_LAT_P;
+        private System.Windows.Forms.Label label31;
+        private System.Windows.Forms.GroupBox groupBox20;
+        private System.Windows.Forms.NumericUpDown STB_YAW_IMAX;
+        private System.Windows.Forms.Label label32;
+        private System.Windows.Forms.NumericUpDown STB_YAW_I;
+        private System.Windows.Forms.Label label34;
+        private System.Windows.Forms.NumericUpDown STB_YAW_P;
+        private System.Windows.Forms.Label label35;
+        private System.Windows.Forms.GroupBox groupBox21;
+        private System.Windows.Forms.NumericUpDown STAB_D;
+        private System.Windows.Forms.Label lblSTAB_D;
+        private System.Windows.Forms.NumericUpDown STB_PIT_IMAX;
+        private System.Windows.Forms.Label label36;
+        private System.Windows.Forms.NumericUpDown STB_PIT_I;
+        private System.Windows.Forms.Label label41;
+        private System.Windows.Forms.NumericUpDown STB_PIT_P;
+        private System.Windows.Forms.Label label42;
+        private System.Windows.Forms.GroupBox groupBox22;
+        private System.Windows.Forms.NumericUpDown STB_RLL_IMAX;
+        private System.Windows.Forms.Label label43;
+        private System.Windows.Forms.NumericUpDown STB_RLL_I;
+        private System.Windows.Forms.Label label45;
+        private System.Windows.Forms.NumericUpDown STB_RLL_P;
+        private System.Windows.Forms.Label label46;
+        private System.Windows.Forms.GroupBox groupBox23;
+        private System.Windows.Forms.NumericUpDown RATE_YAW_D;
+        private System.Windows.Forms.Label label10;
+        private System.Windows.Forms.NumericUpDown RATE_YAW_IMAX;
+        private System.Windows.Forms.Label label47;
+        private System.Windows.Forms.NumericUpDown RATE_YAW_I;
+        private System.Windows.Forms.Label label77;
+        private System.Windows.Forms.NumericUpDown RATE_YAW_P;
+        private System.Windows.Forms.Label label82;
+        private System.Windows.Forms.GroupBox groupBox24;
+        private System.Windows.Forms.NumericUpDown RATE_PIT_D;
+        private System.Windows.Forms.Label label11;
+        private System.Windows.Forms.NumericUpDown RATE_PIT_IMAX;
+        private System.Windows.Forms.Label label84;
+        private System.Windows.Forms.NumericUpDown RATE_PIT_I;
+        private System.Windows.Forms.Label label86;
+        private System.Windows.Forms.NumericUpDown RATE_PIT_P;
+        private System.Windows.Forms.Label label87;
+        private System.Windows.Forms.GroupBox groupBox25;
+        private System.Windows.Forms.NumericUpDown RATE_RLL_D;
+        private System.Windows.Forms.Label label17;
+        private System.Windows.Forms.NumericUpDown RATE_RLL_IMAX;
+        private System.Windows.Forms.Label label88;
+        private System.Windows.Forms.NumericUpDown RATE_RLL_I;
+        private System.Windows.Forms.Label label90;
+        private System.Windows.Forms.NumericUpDown RATE_RLL_P;
+        private System.Windows.Forms.Label label91;
+        private System.Windows.Forms.ToolTip toolTip1;
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs
new file mode 100644
index 0000000000000000000000000000000000000000..606a5f34d42c32dc19cd940e66647db38d0e4ac7
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs
@@ -0,0 +1,349 @@
+using System;
+using System.Collections.Generic;
+using System.ComponentModel;
+using System.Drawing;
+using System.Data;
+using System.Linq;
+using System.Text;
+using System.Windows.Forms;
+using ArdupilotMega.Controls.BackstageView;
+using System.Collections;
+
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    public partial class ConfigArducopter : BackStageViewContentPanel
+    {
+        Hashtable changes = new Hashtable();
+        static Hashtable tooltips = new Hashtable();
+        internal bool startup = true;
+
+
+        public ConfigArducopter()
+        {
+            InitializeComponent();
+        }
+
+        public struct paramsettings // hk's
+        {
+            public string name;
+            public float minvalue;
+            public float maxvalue;
+            public float normalvalue;
+            public float scale;
+            public string desc;
+        }
+
+        private void ConfigArducopter_Load(object sender, EventArgs e)
+        {
+            if (!MainV2.comPort.BaseStream.IsOpen)
+            {
+                this.Enabled = false;
+                return;
+            }
+            else
+            {
+                if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
+                {
+                    this.Enabled = true;
+                }
+                else
+                {
+                    this.Enabled = false;
+                    return;
+                }
+            }
+
+            startup = true;
+
+            changes.Clear();
+
+            // read tooltips
+            if (tooltips.Count == 0)
+                readToolTips();
+
+            // ensure the fields are populated before setting them
+            CH7_OPT.DataSource = Enum.GetNames(typeof(Common.ac2ch7modes));
+            TUNE.DataSource = Enum.GetNames(typeof(Common.ac2ch6modes));
+
+            // prefill all fields
+            processToScreen();
+
+            startup = false;
+        }
+
+        void readToolTips()
+        {
+            System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Configuration));
+
+            string data = resources.GetString("MAVParam");
+
+            if (data == null)
+            {
+                data = global::ArdupilotMega.Properties.Resources.MAVParam;
+            }
+
+            string[] tips = data.Split(new char[] { '\r', '\n' }, StringSplitOptions.RemoveEmptyEntries);
+
+            foreach (var tip in tips)
+            {
+                if (!tip.StartsWith("||"))
+                    continue;
+
+                string[] cols = tip.Split(new string[] { "||" }, 9, StringSplitOptions.None);
+
+                if (cols.Length >= 8)
+                {
+                    paramsettings param = new paramsettings();
+                    try
+                    {
+                        param.name = cols[1];
+                        param.desc = AddNewLinesForTooltip(cols[7]);
+                        param.scale = float.Parse(cols[5]);
+                        param.minvalue = float.Parse(cols[2]);
+                        param.maxvalue = float.Parse(cols[3]);
+                        param.normalvalue = float.Parse(cols[4]);
+                    }
+                    catch { }
+                    tooltips[cols[1]] = param;
+                }
+
+            }
+        }
+
+        // from http://stackoverflow.com/questions/2512781/winforms-big-paragraph-tooltip/2512895#2512895
+        private const int maximumSingleLineTooltipLength = 50;
+
+        private static string AddNewLinesForTooltip(string text)
+        {
+            if (text.Length < maximumSingleLineTooltipLength)
+                return text;
+            int lineLength = (int)Math.Sqrt((double)text.Length) * 2;
+            StringBuilder sb = new StringBuilder();
+            int currentLinePosition = 0;
+            for (int textIndex = 0; textIndex < text.Length; textIndex++)
+            {
+                // If we have reached the target line length and the next      
+                // character is whitespace then begin a new line.   
+                if (currentLinePosition >= lineLength &&
+                    char.IsWhiteSpace(text[textIndex]))
+                {
+                    sb.Append(Environment.NewLine);
+                    currentLinePosition = 0;
+                }
+                // If we have just started a new line, skip all the whitespace.    
+                if (currentLinePosition == 0)
+                    while (textIndex < text.Length && char.IsWhiteSpace(text[textIndex]))
+                        textIndex++;
+                // Append the next character.     
+                if (textIndex < text.Length) sb.Append(text[textIndex]);
+                currentLinePosition++;
+            }
+            return sb.ToString();
+        }
+
+        void disableNumericUpDownControls(Control inctl)
+        {
+            foreach (Control ctl in inctl.Controls)
+            {
+                if (ctl.Controls.Count > 0)
+                {
+                    disableNumericUpDownControls(ctl);
+                }
+                if (ctl.GetType() == typeof(NumericUpDown))
+                {
+                    ctl.Enabled = false;
+                }
+            }
+        }
+
+        internal void processToScreen()
+        {
+            toolTip1.RemoveAll();
+
+            disableNumericUpDownControls(this);
+
+
+            // process hashdefines and update display
+            foreach (string value in MainV2.comPort.param.Keys)
+            {
+                if (value == null || value == "")
+                    continue;
+
+                //System.Diagnostics.Debug.WriteLine("Doing: " + value);
+
+
+                string name = value;
+                Control[] text = this.Controls.Find(name, true);
+                foreach (Control ctl in text)
+                {
+                    try
+                    {
+                        if (ctl.GetType() == typeof(NumericUpDown))
+                        {
+
+                            NumericUpDown thisctl = ((NumericUpDown)ctl);
+                            thisctl.Maximum = 9000;
+                            thisctl.Minimum = -9000;
+                            thisctl.Value = (decimal)(float)MainV2.comPort.param[value];
+                            thisctl.Increment = (decimal)0.001;
+                            if (thisctl.Name.EndsWith("_P") || thisctl.Name.EndsWith("_I") || thisctl.Name.EndsWith("_D")
+                                || thisctl.Name.EndsWith("_LOW") || thisctl.Name.EndsWith("_HIGH") || thisctl.Value == 0
+                                || thisctl.Value.ToString("0.###", new System.Globalization.CultureInfo("en-US")).Contains("."))
+                            {
+                                thisctl.DecimalPlaces = 3;
+                            }
+                            else
+                            {
+                                thisctl.Increment = (decimal)1;
+                                thisctl.DecimalPlaces = 1;
+                            }
+
+                            if (thisctl.Name.EndsWith("_IMAX"))
+                            {
+                                thisctl.Maximum = 180;
+                                thisctl.Minimum = -180;
+                            }
+
+                            thisctl.Enabled = true;
+
+                            thisctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
+                            thisctl.Validated += null;
+                            if (tooltips[value] != null)
+                            {
+                                try
+                                {
+                                    toolTip1.SetToolTip(ctl, ((paramsettings)tooltips[value]).desc);
+                                }
+                                catch { }
+                            }
+                            thisctl.Validated += new EventHandler(EEPROM_View_float_TextChanged);
+
+                        }
+                        else if (ctl.GetType() == typeof(ComboBox))
+                        {
+
+                            ComboBox thisctl = ((ComboBox)ctl);
+
+                            thisctl.SelectedIndex = (int)(float)MainV2.comPort.param[value];
+
+                            thisctl.Validated += new EventHandler(ComboBox_Validated);
+
+                            thisctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
+                        }
+                    }
+                    catch { }
+
+                }
+                if (text.Length == 0)
+                {
+                    //Console.WriteLine(name + " not found");
+                }
+
+            }
+        }
+
+               void ComboBox_Validated(object sender, EventArgs e)
+        {
+            EEPROM_View_float_TextChanged(sender, e);
+        }
+
+        void Configuration_Validating(object sender, CancelEventArgs e)
+        {
+            EEPROM_View_float_TextChanged(sender, e);
+        }
+
+        internal void EEPROM_View_float_TextChanged(object sender, EventArgs e)
+        {
+            if (startup == true)
+                return;
+
+            float value = 0;
+            string name = ((Control)sender).Name;
+
+            // do domainupdown state check
+            try
+            {
+                if (sender.GetType() == typeof(NumericUpDown))
+                {
+                    value = float.Parse(((Control)sender).Text);
+                    changes[name] = value;
+                }
+                else if (sender.GetType() == typeof(ComboBox))
+                {
+                    value = ((ComboBox)sender).SelectedIndex;
+                    changes[name] = value;
+                }
+                ((Control)sender).BackColor = Color.Green;
+            }
+            catch (Exception)
+            {
+                ((Control)sender).BackColor = Color.Red;
+            }
+
+            try
+            {
+                // enable roll and pitch pairing for ac2
+                if (CHK_lockrollpitch.Checked)
+                {
+                    if (name.StartsWith("RATE_") || name.StartsWith("STB_") || name.StartsWith("ACRO_"))
+                    {
+                        if (name.Contains("_RLL_"))
+                        {
+                            string newname = name.Replace("_RLL_", "_PIT_");
+                            Control[] arr = this.Controls.Find(newname, true);
+                            changes[newname] = float.Parse(((Control)sender).Text);
+
+                            if (arr.Length > 0)
+                            {
+                                arr[0].Text = ((Control)sender).Text;
+                                arr[0].BackColor = Color.Green;
+                            }
+
+                        }
+                        else if (name.Contains("_PIT_"))
+                        {
+                            string newname = name.Replace("_PIT_", "_RLL_");
+                            Control[] arr = this.Controls.Find(newname, true);
+                            changes[newname] = float.Parse(((Control)sender).Text);
+
+                            if (arr.Length > 0)
+                            {
+                                arr[0].Text = ((Control)sender).Text;
+                                arr[0].BackColor = Color.Green;
+                            }
+                        }
+                    }
+                }
+                // keep nav_lat and nav_lon paired
+                if (name.Contains("NAV_LAT_"))
+                {
+                    string newname = name.Replace("NAV_LAT_", "NAV_LON_");
+                    Control[] arr = this.Controls.Find(newname, true);
+                    changes[newname] = float.Parse(((Control)sender).Text);
+
+                    if (arr.Length > 0)
+                    {
+                        arr[0].Text = ((Control)sender).Text;
+                        arr[0].BackColor = Color.Green;
+                    }
+                }
+                // keep nav_lat and nav_lon paired
+                if (name.Contains("HLD_LAT_"))
+                {
+                    string newname = name.Replace("HLD_LAT_", "HLD_LON_");
+                    Control[] arr = this.Controls.Find(newname, true);
+                    changes[newname] = float.Parse(((Control)sender).Text);
+
+                    if (arr.Length > 0)
+                    {
+                        arr[0].Text = ((Control)sender).Text;
+                        arr[0].BackColor = Color.Green;
+                    }
+                }
+            }
+            catch { }
+        }
+      
+        
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx
new file mode 100644
index 0000000000000000000000000000000000000000..271670364af059e95ad645d78fad7553ecbd0d09
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx
@@ -0,0 +1,123 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
+    <value>17, 17</value>
+  </metadata>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.Designer.cs
new file mode 100644
index 0000000000000000000000000000000000000000..f30b039741e027ba75455bbfab1439f67891aea1
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.Designer.cs
@@ -0,0 +1,1274 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    partial class ConfigArduplane
+    {
+        /// <summary> 
+        /// Required designer variable.
+        /// </summary>
+        private System.ComponentModel.IContainer components = null;
+
+        /// <summary> 
+        /// Clean up any resources being used.
+        /// </summary>
+        /// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
+        protected override void Dispose(bool disposing)
+        {
+            if (disposing && (components != null))
+            {
+                components.Dispose();
+            }
+            base.Dispose(disposing);
+        }
+
+        #region Component Designer generated code
+
+        /// <summary> 
+        /// Required method for Designer support - do not modify 
+        /// the contents of this method with the code editor.
+        /// </summary>
+        private void InitializeComponent()
+        {
+            this.components = new System.ComponentModel.Container();
+            this.groupBox3 = new System.Windows.Forms.GroupBox();
+            this.THR_FS_VALUE = new System.Windows.Forms.NumericUpDown();
+            this.label5 = new System.Windows.Forms.Label();
+            this.THR_MAX = new System.Windows.Forms.NumericUpDown();
+            this.label6 = new System.Windows.Forms.Label();
+            this.THR_MIN = new System.Windows.Forms.NumericUpDown();
+            this.label7 = new System.Windows.Forms.Label();
+            this.TRIM_THROTTLE = new System.Windows.Forms.NumericUpDown();
+            this.label8 = new System.Windows.Forms.Label();
+            this.groupBox1 = new System.Windows.Forms.GroupBox();
+            this.ARSPD_RATIO = new System.Windows.Forms.NumericUpDown();
+            this.label1 = new System.Windows.Forms.Label();
+            this.ARSPD_FBW_MAX = new System.Windows.Forms.NumericUpDown();
+            this.label2 = new System.Windows.Forms.Label();
+            this.ARSPD_FBW_MIN = new System.Windows.Forms.NumericUpDown();
+            this.label3 = new System.Windows.Forms.Label();
+            this.TRIM_ARSPD_CM = new System.Windows.Forms.NumericUpDown();
+            this.label4 = new System.Windows.Forms.Label();
+            this.groupBox2 = new System.Windows.Forms.GroupBox();
+            this.LIM_PITCH_MIN = new System.Windows.Forms.NumericUpDown();
+            this.label39 = new System.Windows.Forms.Label();
+            this.LIM_PITCH_MAX = new System.Windows.Forms.NumericUpDown();
+            this.label38 = new System.Windows.Forms.Label();
+            this.LIM_ROLL_CD = new System.Windows.Forms.NumericUpDown();
+            this.label37 = new System.Windows.Forms.Label();
+            this.groupBox15 = new System.Windows.Forms.GroupBox();
+            this.XTRK_ANGLE_CD = new System.Windows.Forms.NumericUpDown();
+            this.label79 = new System.Windows.Forms.Label();
+            this.XTRK_GAIN_SC = new System.Windows.Forms.NumericUpDown();
+            this.label80 = new System.Windows.Forms.Label();
+            this.groupBox16 = new System.Windows.Forms.GroupBox();
+            this.KFF_PTCH2THR = new System.Windows.Forms.NumericUpDown();
+            this.label83 = new System.Windows.Forms.Label();
+            this.KFF_RDDRMIX = new System.Windows.Forms.NumericUpDown();
+            this.label78 = new System.Windows.Forms.Label();
+            this.KFF_PTCHCOMP = new System.Windows.Forms.NumericUpDown();
+            this.label81 = new System.Windows.Forms.Label();
+            this.groupBox14 = new System.Windows.Forms.GroupBox();
+            this.ENRGY2THR_IMAX = new System.Windows.Forms.NumericUpDown();
+            this.label73 = new System.Windows.Forms.Label();
+            this.ENRGY2THR_D = new System.Windows.Forms.NumericUpDown();
+            this.label74 = new System.Windows.Forms.Label();
+            this.ENRGY2THR_I = new System.Windows.Forms.NumericUpDown();
+            this.label75 = new System.Windows.Forms.Label();
+            this.ENRGY2THR_P = new System.Windows.Forms.NumericUpDown();
+            this.label76 = new System.Windows.Forms.Label();
+            this.groupBox13 = new System.Windows.Forms.GroupBox();
+            this.ALT2PTCH_IMAX = new System.Windows.Forms.NumericUpDown();
+            this.label69 = new System.Windows.Forms.Label();
+            this.ALT2PTCH_D = new System.Windows.Forms.NumericUpDown();
+            this.label70 = new System.Windows.Forms.Label();
+            this.ALT2PTCH_I = new System.Windows.Forms.NumericUpDown();
+            this.label71 = new System.Windows.Forms.Label();
+            this.ALT2PTCH_P = new System.Windows.Forms.NumericUpDown();
+            this.label72 = new System.Windows.Forms.Label();
+            this.groupBox12 = new System.Windows.Forms.GroupBox();
+            this.ARSP2PTCH_IMAX = new System.Windows.Forms.NumericUpDown();
+            this.label65 = new System.Windows.Forms.Label();
+            this.ARSP2PTCH_D = new System.Windows.Forms.NumericUpDown();
+            this.label66 = new System.Windows.Forms.Label();
+            this.ARSP2PTCH_I = new System.Windows.Forms.NumericUpDown();
+            this.label67 = new System.Windows.Forms.Label();
+            this.ARSP2PTCH_P = new System.Windows.Forms.NumericUpDown();
+            this.label68 = new System.Windows.Forms.Label();
+            this.groupBox11 = new System.Windows.Forms.GroupBox();
+            this.HDNG2RLL_IMAX = new System.Windows.Forms.NumericUpDown();
+            this.label61 = new System.Windows.Forms.Label();
+            this.HDNG2RLL_D = new System.Windows.Forms.NumericUpDown();
+            this.label62 = new System.Windows.Forms.Label();
+            this.HDNG2RLL_I = new System.Windows.Forms.NumericUpDown();
+            this.label63 = new System.Windows.Forms.Label();
+            this.HDNG2RLL_P = new System.Windows.Forms.NumericUpDown();
+            this.label64 = new System.Windows.Forms.Label();
+            this.groupBox10 = new System.Windows.Forms.GroupBox();
+            this.YW2SRV_IMAX = new System.Windows.Forms.NumericUpDown();
+            this.label57 = new System.Windows.Forms.Label();
+            this.YW2SRV_D = new System.Windows.Forms.NumericUpDown();
+            this.label58 = new System.Windows.Forms.Label();
+            this.YW2SRV_I = new System.Windows.Forms.NumericUpDown();
+            this.label59 = new System.Windows.Forms.Label();
+            this.YW2SRV_P = new System.Windows.Forms.NumericUpDown();
+            this.label60 = new System.Windows.Forms.Label();
+            this.groupBox9 = new System.Windows.Forms.GroupBox();
+            this.PTCH2SRV_IMAX = new System.Windows.Forms.NumericUpDown();
+            this.label53 = new System.Windows.Forms.Label();
+            this.PTCH2SRV_D = new System.Windows.Forms.NumericUpDown();
+            this.label54 = new System.Windows.Forms.Label();
+            this.PTCH2SRV_I = new System.Windows.Forms.NumericUpDown();
+            this.label55 = new System.Windows.Forms.Label();
+            this.PTCH2SRV_P = new System.Windows.Forms.NumericUpDown();
+            this.label56 = new System.Windows.Forms.Label();
+            this.groupBox8 = new System.Windows.Forms.GroupBox();
+            this.RLL2SRV_IMAX = new System.Windows.Forms.NumericUpDown();
+            this.label49 = new System.Windows.Forms.Label();
+            this.RLL2SRV_D = new System.Windows.Forms.NumericUpDown();
+            this.label50 = new System.Windows.Forms.Label();
+            this.RLL2SRV_I = new System.Windows.Forms.NumericUpDown();
+            this.label51 = new System.Windows.Forms.Label();
+            this.RLL2SRV_P = new System.Windows.Forms.NumericUpDown();
+            this.label52 = new System.Windows.Forms.Label();
+            this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
+            this.groupBox3.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.THR_FS_VALUE)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.THR_MAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.THR_MIN)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.TRIM_THROTTLE)).BeginInit();
+            this.groupBox1.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.ARSPD_RATIO)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MIN)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.TRIM_ARSPD_CM)).BeginInit();
+            this.groupBox2.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MIN)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.LIM_ROLL_CD)).BeginInit();
+            this.groupBox15.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.XTRK_ANGLE_CD)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.XTRK_GAIN_SC)).BeginInit();
+            this.groupBox16.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.KFF_PTCH2THR)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.KFF_RDDRMIX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.KFF_PTCHCOMP)).BeginInit();
+            this.groupBox14.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_IMAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_D)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_I)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_P)).BeginInit();
+            this.groupBox13.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_IMAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_D)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_I)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_P)).BeginInit();
+            this.groupBox12.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_IMAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_D)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_I)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_P)).BeginInit();
+            this.groupBox11.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_IMAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_D)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_I)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_P)).BeginInit();
+            this.groupBox10.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_IMAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_D)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_I)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_P)).BeginInit();
+            this.groupBox9.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_IMAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_D)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_I)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_P)).BeginInit();
+            this.groupBox8.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_IMAX)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_D)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_I)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_P)).BeginInit();
+            this.SuspendLayout();
+            // 
+            // groupBox3
+            // 
+            this.groupBox3.Controls.Add(this.THR_FS_VALUE);
+            this.groupBox3.Controls.Add(this.label5);
+            this.groupBox3.Controls.Add(this.THR_MAX);
+            this.groupBox3.Controls.Add(this.label6);
+            this.groupBox3.Controls.Add(this.THR_MIN);
+            this.groupBox3.Controls.Add(this.label7);
+            this.groupBox3.Controls.Add(this.TRIM_THROTTLE);
+            this.groupBox3.Controls.Add(this.label8);
+            this.groupBox3.Location = new System.Drawing.Point(413, 231);
+            this.groupBox3.Name = "groupBox3";
+            this.groupBox3.Size = new System.Drawing.Size(195, 108);
+            this.groupBox3.TabIndex = 12;
+            this.groupBox3.TabStop = false;
+            this.groupBox3.Text = "Throttle 0-100%";
+            // 
+            // THR_FS_VALUE
+            // 
+            this.THR_FS_VALUE.Location = new System.Drawing.Point(111, 82);
+            this.THR_FS_VALUE.Name = "THR_FS_VALUE";
+            this.THR_FS_VALUE.Size = new System.Drawing.Size(78, 20);
+            this.THR_FS_VALUE.TabIndex = 11;
+            // 
+            // label5
+            // 
+            this.label5.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label5.Location = new System.Drawing.Point(6, 86);
+            this.label5.Name = "label5";
+            this.label5.Size = new System.Drawing.Size(50, 13);
+            this.label5.TabIndex = 12;
+            this.label5.Text = "FS Value";
+            // 
+            // THR_MAX
+            // 
+            this.THR_MAX.Location = new System.Drawing.Point(111, 59);
+            this.THR_MAX.Name = "THR_MAX";
+            this.THR_MAX.Size = new System.Drawing.Size(78, 20);
+            this.THR_MAX.TabIndex = 9;
+            // 
+            // label6
+            // 
+            this.label6.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label6.Location = new System.Drawing.Point(6, 63);
+            this.label6.Name = "label6";
+            this.label6.Size = new System.Drawing.Size(27, 13);
+            this.label6.TabIndex = 13;
+            this.label6.Text = "Max";
+            // 
+            // THR_MIN
+            // 
+            this.THR_MIN.Location = new System.Drawing.Point(111, 36);
+            this.THR_MIN.Name = "THR_MIN";
+            this.THR_MIN.Size = new System.Drawing.Size(78, 20);
+            this.THR_MIN.TabIndex = 7;
+            // 
+            // label7
+            // 
+            this.label7.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label7.Location = new System.Drawing.Point(6, 40);
+            this.label7.Name = "label7";
+            this.label7.Size = new System.Drawing.Size(24, 13);
+            this.label7.TabIndex = 14;
+            this.label7.Text = "Min";
+            // 
+            // TRIM_THROTTLE
+            // 
+            this.TRIM_THROTTLE.Location = new System.Drawing.Point(111, 13);
+            this.TRIM_THROTTLE.Name = "TRIM_THROTTLE";
+            this.TRIM_THROTTLE.Size = new System.Drawing.Size(78, 20);
+            this.TRIM_THROTTLE.TabIndex = 5;
+            // 
+            // label8
+            // 
+            this.label8.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label8.Location = new System.Drawing.Point(6, 17);
+            this.label8.Name = "label8";
+            this.label8.Size = new System.Drawing.Size(36, 13);
+            this.label8.TabIndex = 15;
+            this.label8.Text = "Cruise";
+            // 
+            // groupBox1
+            // 
+            this.groupBox1.Controls.Add(this.ARSPD_RATIO);
+            this.groupBox1.Controls.Add(this.label1);
+            this.groupBox1.Controls.Add(this.ARSPD_FBW_MAX);
+            this.groupBox1.Controls.Add(this.label2);
+            this.groupBox1.Controls.Add(this.ARSPD_FBW_MIN);
+            this.groupBox1.Controls.Add(this.label3);
+            this.groupBox1.Controls.Add(this.TRIM_ARSPD_CM);
+            this.groupBox1.Controls.Add(this.label4);
+            this.groupBox1.Location = new System.Drawing.Point(414, 339);
+            this.groupBox1.Name = "groupBox1";
+            this.groupBox1.Size = new System.Drawing.Size(195, 108);
+            this.groupBox1.TabIndex = 13;
+            this.groupBox1.TabStop = false;
+            this.groupBox1.Text = "Airspeed m/s";
+            // 
+            // ARSPD_RATIO
+            // 
+            this.ARSPD_RATIO.Location = new System.Drawing.Point(111, 82);
+            this.ARSPD_RATIO.Name = "ARSPD_RATIO";
+            this.ARSPD_RATIO.Size = new System.Drawing.Size(78, 20);
+            this.ARSPD_RATIO.TabIndex = 0;
+            // 
+            // label1
+            // 
+            this.label1.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label1.Location = new System.Drawing.Point(6, 87);
+            this.label1.Name = "label1";
+            this.label1.Size = new System.Drawing.Size(32, 13);
+            this.label1.TabIndex = 1;
+            this.label1.Text = "Ratio";
+            // 
+            // ARSPD_FBW_MAX
+            // 
+            this.ARSPD_FBW_MAX.Location = new System.Drawing.Point(111, 59);
+            this.ARSPD_FBW_MAX.Name = "ARSPD_FBW_MAX";
+            this.ARSPD_FBW_MAX.Size = new System.Drawing.Size(78, 20);
+            this.ARSPD_FBW_MAX.TabIndex = 2;
+            // 
+            // label2
+            // 
+            this.label2.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label2.Location = new System.Drawing.Point(6, 59);
+            this.label2.Name = "label2";
+            this.label2.Size = new System.Drawing.Size(53, 13);
+            this.label2.TabIndex = 3;
+            this.label2.Text = "FBW max";
+            // 
+            // ARSPD_FBW_MIN
+            // 
+            this.ARSPD_FBW_MIN.Location = new System.Drawing.Point(111, 36);
+            this.ARSPD_FBW_MIN.Name = "ARSPD_FBW_MIN";
+            this.ARSPD_FBW_MIN.Size = new System.Drawing.Size(78, 20);
+            this.ARSPD_FBW_MIN.TabIndex = 4;
+            // 
+            // label3
+            // 
+            this.label3.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label3.Location = new System.Drawing.Point(6, 40);
+            this.label3.Name = "label3";
+            this.label3.Size = new System.Drawing.Size(50, 13);
+            this.label3.TabIndex = 5;
+            this.label3.Text = "FBW min";
+            // 
+            // TRIM_ARSPD_CM
+            // 
+            this.TRIM_ARSPD_CM.Location = new System.Drawing.Point(111, 13);
+            this.TRIM_ARSPD_CM.Name = "TRIM_ARSPD_CM";
+            this.TRIM_ARSPD_CM.Size = new System.Drawing.Size(78, 20);
+            this.TRIM_ARSPD_CM.TabIndex = 5;
+            // 
+            // label4
+            // 
+            this.label4.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label4.Location = new System.Drawing.Point(6, 17);
+            this.label4.Name = "label4";
+            this.label4.Size = new System.Drawing.Size(64, 13);
+            this.label4.TabIndex = 6;
+            this.label4.Text = "Cruise";
+            // 
+            // groupBox2
+            // 
+            this.groupBox2.Controls.Add(this.LIM_PITCH_MIN);
+            this.groupBox2.Controls.Add(this.label39);
+            this.groupBox2.Controls.Add(this.LIM_PITCH_MAX);
+            this.groupBox2.Controls.Add(this.label38);
+            this.groupBox2.Controls.Add(this.LIM_ROLL_CD);
+            this.groupBox2.Controls.Add(this.label37);
+            this.groupBox2.Location = new System.Drawing.Point(213, 339);
+            this.groupBox2.Name = "groupBox2";
+            this.groupBox2.Size = new System.Drawing.Size(195, 108);
+            this.groupBox2.TabIndex = 14;
+            this.groupBox2.TabStop = false;
+            this.groupBox2.Text = "Navigation Angles";
+            // 
+            // LIM_PITCH_MIN
+            // 
+            this.LIM_PITCH_MIN.Location = new System.Drawing.Point(111, 59);
+            this.LIM_PITCH_MIN.Name = "LIM_PITCH_MIN";
+            this.LIM_PITCH_MIN.Size = new System.Drawing.Size(78, 20);
+            this.LIM_PITCH_MIN.TabIndex = 9;
+            // 
+            // label39
+            // 
+            this.label39.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label39.Location = new System.Drawing.Point(6, 63);
+            this.label39.Name = "label39";
+            this.label39.Size = new System.Drawing.Size(51, 13);
+            this.label39.TabIndex = 10;
+            this.label39.Text = "Pitch Min";
+            // 
+            // LIM_PITCH_MAX
+            // 
+            this.LIM_PITCH_MAX.Location = new System.Drawing.Point(111, 36);
+            this.LIM_PITCH_MAX.Name = "LIM_PITCH_MAX";
+            this.LIM_PITCH_MAX.Size = new System.Drawing.Size(78, 20);
+            this.LIM_PITCH_MAX.TabIndex = 7;
+            // 
+            // label38
+            // 
+            this.label38.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label38.Location = new System.Drawing.Point(6, 40);
+            this.label38.Name = "label38";
+            this.label38.Size = new System.Drawing.Size(54, 13);
+            this.label38.TabIndex = 11;
+            this.label38.Text = "Pitch Max";
+            // 
+            // LIM_ROLL_CD
+            // 
+            this.LIM_ROLL_CD.Location = new System.Drawing.Point(111, 13);
+            this.LIM_ROLL_CD.Name = "LIM_ROLL_CD";
+            this.LIM_ROLL_CD.Size = new System.Drawing.Size(78, 20);
+            this.LIM_ROLL_CD.TabIndex = 5;
+            // 
+            // label37
+            // 
+            this.label37.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label37.Location = new System.Drawing.Point(6, 17);
+            this.label37.Name = "label37";
+            this.label37.Size = new System.Drawing.Size(55, 13);
+            this.label37.TabIndex = 12;
+            this.label37.Text = "Bank Max";
+            // 
+            // groupBox15
+            // 
+            this.groupBox15.Controls.Add(this.XTRK_ANGLE_CD);
+            this.groupBox15.Controls.Add(this.label79);
+            this.groupBox15.Controls.Add(this.XTRK_GAIN_SC);
+            this.groupBox15.Controls.Add(this.label80);
+            this.groupBox15.Location = new System.Drawing.Point(12, 339);
+            this.groupBox15.Name = "groupBox15";
+            this.groupBox15.Size = new System.Drawing.Size(195, 108);
+            this.groupBox15.TabIndex = 15;
+            this.groupBox15.TabStop = false;
+            this.groupBox15.Text = "Xtrack Pids";
+            // 
+            // XTRK_ANGLE_CD
+            // 
+            this.XTRK_ANGLE_CD.Location = new System.Drawing.Point(111, 36);
+            this.XTRK_ANGLE_CD.Name = "XTRK_ANGLE_CD";
+            this.XTRK_ANGLE_CD.Size = new System.Drawing.Size(78, 20);
+            this.XTRK_ANGLE_CD.TabIndex = 7;
+            // 
+            // label79
+            // 
+            this.label79.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label79.Location = new System.Drawing.Point(6, 40);
+            this.label79.Name = "label79";
+            this.label79.Size = new System.Drawing.Size(61, 13);
+            this.label79.TabIndex = 8;
+            this.label79.Text = "Entry Angle";
+            // 
+            // XTRK_GAIN_SC
+            // 
+            this.XTRK_GAIN_SC.Location = new System.Drawing.Point(111, 13);
+            this.XTRK_GAIN_SC.Name = "XTRK_GAIN_SC";
+            this.XTRK_GAIN_SC.Size = new System.Drawing.Size(78, 20);
+            this.XTRK_GAIN_SC.TabIndex = 5;
+            // 
+            // label80
+            // 
+            this.label80.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label80.Location = new System.Drawing.Point(6, 17);
+            this.label80.Name = "label80";
+            this.label80.Size = new System.Drawing.Size(52, 13);
+            this.label80.TabIndex = 9;
+            this.label80.Text = "Gain (cm)";
+            // 
+            // groupBox16
+            // 
+            this.groupBox16.Controls.Add(this.KFF_PTCH2THR);
+            this.groupBox16.Controls.Add(this.label83);
+            this.groupBox16.Controls.Add(this.KFF_RDDRMIX);
+            this.groupBox16.Controls.Add(this.label78);
+            this.groupBox16.Controls.Add(this.KFF_PTCHCOMP);
+            this.groupBox16.Controls.Add(this.label81);
+            this.groupBox16.Location = new System.Drawing.Point(213, 231);
+            this.groupBox16.Name = "groupBox16";
+            this.groupBox16.Size = new System.Drawing.Size(195, 108);
+            this.groupBox16.TabIndex = 16;
+            this.groupBox16.TabStop = false;
+            this.groupBox16.Text = "Other Mix\'s";
+            // 
+            // KFF_PTCH2THR
+            // 
+            this.KFF_PTCH2THR.Location = new System.Drawing.Point(111, 13);
+            this.KFF_PTCH2THR.Name = "KFF_PTCH2THR";
+            this.KFF_PTCH2THR.Size = new System.Drawing.Size(78, 20);
+            this.KFF_PTCH2THR.TabIndex = 13;
+            // 
+            // label83
+            // 
+            this.label83.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label83.Location = new System.Drawing.Point(6, 17);
+            this.label83.Name = "label83";
+            this.label83.Size = new System.Drawing.Size(36, 13);
+            this.label83.TabIndex = 14;
+            this.label83.Text = "P to T";
+            // 
+            // KFF_RDDRMIX
+            // 
+            this.KFF_RDDRMIX.Location = new System.Drawing.Point(111, 59);
+            this.KFF_RDDRMIX.Name = "KFF_RDDRMIX";
+            this.KFF_RDDRMIX.Size = new System.Drawing.Size(78, 20);
+            this.KFF_RDDRMIX.TabIndex = 9;
+            // 
+            // label78
+            // 
+            this.label78.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label78.Location = new System.Drawing.Point(6, 63);
+            this.label78.Name = "label78";
+            this.label78.Size = new System.Drawing.Size(61, 13);
+            this.label78.TabIndex = 15;
+            this.label78.Text = "Rudder Mix";
+            // 
+            // KFF_PTCHCOMP
+            // 
+            this.KFF_PTCHCOMP.Location = new System.Drawing.Point(111, 36);
+            this.KFF_PTCHCOMP.Name = "KFF_PTCHCOMP";
+            this.KFF_PTCHCOMP.Size = new System.Drawing.Size(78, 20);
+            this.KFF_PTCHCOMP.TabIndex = 7;
+            // 
+            // label81
+            // 
+            this.label81.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label81.Location = new System.Drawing.Point(6, 40);
+            this.label81.Name = "label81";
+            this.label81.Size = new System.Drawing.Size(61, 13);
+            this.label81.TabIndex = 16;
+            this.label81.Text = "Pitch Comp";
+            // 
+            // groupBox14
+            // 
+            this.groupBox14.Controls.Add(this.ENRGY2THR_IMAX);
+            this.groupBox14.Controls.Add(this.label73);
+            this.groupBox14.Controls.Add(this.ENRGY2THR_D);
+            this.groupBox14.Controls.Add(this.label74);
+            this.groupBox14.Controls.Add(this.ENRGY2THR_I);
+            this.groupBox14.Controls.Add(this.label75);
+            this.groupBox14.Controls.Add(this.ENRGY2THR_P);
+            this.groupBox14.Controls.Add(this.label76);
+            this.groupBox14.Location = new System.Drawing.Point(12, 231);
+            this.groupBox14.Name = "groupBox14";
+            this.groupBox14.Size = new System.Drawing.Size(195, 108);
+            this.groupBox14.TabIndex = 17;
+            this.groupBox14.TabStop = false;
+            this.groupBox14.Text = "Energy/Alt Pid";
+            // 
+            // ENRGY2THR_IMAX
+            // 
+            this.ENRGY2THR_IMAX.Location = new System.Drawing.Point(111, 82);
+            this.ENRGY2THR_IMAX.Name = "ENRGY2THR_IMAX";
+            this.ENRGY2THR_IMAX.Size = new System.Drawing.Size(78, 20);
+            this.ENRGY2THR_IMAX.TabIndex = 11;
+            // 
+            // label73
+            // 
+            this.label73.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label73.Location = new System.Drawing.Point(6, 86);
+            this.label73.Name = "label73";
+            this.label73.Size = new System.Drawing.Size(54, 13);
+            this.label73.TabIndex = 12;
+            this.label73.Text = "INT_MAX";
+            // 
+            // ENRGY2THR_D
+            // 
+            this.ENRGY2THR_D.Location = new System.Drawing.Point(111, 59);
+            this.ENRGY2THR_D.Name = "ENRGY2THR_D";
+            this.ENRGY2THR_D.Size = new System.Drawing.Size(78, 20);
+            this.ENRGY2THR_D.TabIndex = 9;
+            // 
+            // label74
+            // 
+            this.label74.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label74.Location = new System.Drawing.Point(6, 63);
+            this.label74.Name = "label74";
+            this.label74.Size = new System.Drawing.Size(15, 13);
+            this.label74.TabIndex = 13;
+            this.label74.Text = "D";
+            // 
+            // ENRGY2THR_I
+            // 
+            this.ENRGY2THR_I.Location = new System.Drawing.Point(111, 36);
+            this.ENRGY2THR_I.Name = "ENRGY2THR_I";
+            this.ENRGY2THR_I.Size = new System.Drawing.Size(78, 20);
+            this.ENRGY2THR_I.TabIndex = 7;
+            // 
+            // label75
+            // 
+            this.label75.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label75.Location = new System.Drawing.Point(6, 40);
+            this.label75.Name = "label75";
+            this.label75.Size = new System.Drawing.Size(10, 13);
+            this.label75.TabIndex = 14;
+            this.label75.Text = "I";
+            // 
+            // ENRGY2THR_P
+            // 
+            this.ENRGY2THR_P.Location = new System.Drawing.Point(111, 13);
+            this.ENRGY2THR_P.Name = "ENRGY2THR_P";
+            this.ENRGY2THR_P.Size = new System.Drawing.Size(78, 20);
+            this.ENRGY2THR_P.TabIndex = 5;
+            // 
+            // label76
+            // 
+            this.label76.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label76.Location = new System.Drawing.Point(6, 17);
+            this.label76.Name = "label76";
+            this.label76.Size = new System.Drawing.Size(14, 13);
+            this.label76.TabIndex = 15;
+            this.label76.Text = "P";
+            // 
+            // groupBox13
+            // 
+            this.groupBox13.Controls.Add(this.ALT2PTCH_IMAX);
+            this.groupBox13.Controls.Add(this.label69);
+            this.groupBox13.Controls.Add(this.ALT2PTCH_D);
+            this.groupBox13.Controls.Add(this.label70);
+            this.groupBox13.Controls.Add(this.ALT2PTCH_I);
+            this.groupBox13.Controls.Add(this.label71);
+            this.groupBox13.Controls.Add(this.ALT2PTCH_P);
+            this.groupBox13.Controls.Add(this.label72);
+            this.groupBox13.Location = new System.Drawing.Point(414, 123);
+            this.groupBox13.Name = "groupBox13";
+            this.groupBox13.Size = new System.Drawing.Size(195, 108);
+            this.groupBox13.TabIndex = 18;
+            this.groupBox13.TabStop = false;
+            this.groupBox13.Text = "Nav Pitch Alt Pid";
+            // 
+            // ALT2PTCH_IMAX
+            // 
+            this.ALT2PTCH_IMAX.Location = new System.Drawing.Point(111, 82);
+            this.ALT2PTCH_IMAX.Name = "ALT2PTCH_IMAX";
+            this.ALT2PTCH_IMAX.Size = new System.Drawing.Size(78, 20);
+            this.ALT2PTCH_IMAX.TabIndex = 0;
+            // 
+            // label69
+            // 
+            this.label69.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label69.Location = new System.Drawing.Point(6, 86);
+            this.label69.Name = "label69";
+            this.label69.Size = new System.Drawing.Size(54, 13);
+            this.label69.TabIndex = 1;
+            this.label69.Text = "INT_MAX";
+            // 
+            // ALT2PTCH_D
+            // 
+            this.ALT2PTCH_D.Location = new System.Drawing.Point(111, 59);
+            this.ALT2PTCH_D.Name = "ALT2PTCH_D";
+            this.ALT2PTCH_D.Size = new System.Drawing.Size(78, 20);
+            this.ALT2PTCH_D.TabIndex = 2;
+            // 
+            // label70
+            // 
+            this.label70.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label70.Location = new System.Drawing.Point(6, 63);
+            this.label70.Name = "label70";
+            this.label70.Size = new System.Drawing.Size(15, 13);
+            this.label70.TabIndex = 3;
+            this.label70.Text = "D";
+            // 
+            // ALT2PTCH_I
+            // 
+            this.ALT2PTCH_I.Location = new System.Drawing.Point(111, 36);
+            this.ALT2PTCH_I.Name = "ALT2PTCH_I";
+            this.ALT2PTCH_I.Size = new System.Drawing.Size(78, 20);
+            this.ALT2PTCH_I.TabIndex = 4;
+            // 
+            // label71
+            // 
+            this.label71.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label71.Location = new System.Drawing.Point(6, 40);
+            this.label71.Name = "label71";
+            this.label71.Size = new System.Drawing.Size(10, 13);
+            this.label71.TabIndex = 5;
+            this.label71.Text = "I";
+            // 
+            // ALT2PTCH_P
+            // 
+            this.ALT2PTCH_P.Location = new System.Drawing.Point(111, 13);
+            this.ALT2PTCH_P.Name = "ALT2PTCH_P";
+            this.ALT2PTCH_P.Size = new System.Drawing.Size(78, 20);
+            this.ALT2PTCH_P.TabIndex = 6;
+            // 
+            // label72
+            // 
+            this.label72.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label72.Location = new System.Drawing.Point(6, 17);
+            this.label72.Name = "label72";
+            this.label72.Size = new System.Drawing.Size(14, 13);
+            this.label72.TabIndex = 7;
+            this.label72.Text = "P";
+            // 
+            // groupBox12
+            // 
+            this.groupBox12.Controls.Add(this.ARSP2PTCH_IMAX);
+            this.groupBox12.Controls.Add(this.label65);
+            this.groupBox12.Controls.Add(this.ARSP2PTCH_D);
+            this.groupBox12.Controls.Add(this.label66);
+            this.groupBox12.Controls.Add(this.ARSP2PTCH_I);
+            this.groupBox12.Controls.Add(this.label67);
+            this.groupBox12.Controls.Add(this.ARSP2PTCH_P);
+            this.groupBox12.Controls.Add(this.label68);
+            this.groupBox12.Location = new System.Drawing.Point(213, 123);
+            this.groupBox12.Name = "groupBox12";
+            this.groupBox12.Size = new System.Drawing.Size(195, 108);
+            this.groupBox12.TabIndex = 19;
+            this.groupBox12.TabStop = false;
+            this.groupBox12.Text = "Nav Pitch AS Pid";
+            // 
+            // ARSP2PTCH_IMAX
+            // 
+            this.ARSP2PTCH_IMAX.Location = new System.Drawing.Point(111, 82);
+            this.ARSP2PTCH_IMAX.Name = "ARSP2PTCH_IMAX";
+            this.ARSP2PTCH_IMAX.Size = new System.Drawing.Size(78, 20);
+            this.ARSP2PTCH_IMAX.TabIndex = 0;
+            // 
+            // label65
+            // 
+            this.label65.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label65.Location = new System.Drawing.Point(6, 86);
+            this.label65.Name = "label65";
+            this.label65.Size = new System.Drawing.Size(54, 13);
+            this.label65.TabIndex = 1;
+            this.label65.Text = "INT_MAX";
+            // 
+            // ARSP2PTCH_D
+            // 
+            this.ARSP2PTCH_D.Location = new System.Drawing.Point(111, 59);
+            this.ARSP2PTCH_D.Name = "ARSP2PTCH_D";
+            this.ARSP2PTCH_D.Size = new System.Drawing.Size(78, 20);
+            this.ARSP2PTCH_D.TabIndex = 2;
+            // 
+            // label66
+            // 
+            this.label66.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label66.Location = new System.Drawing.Point(6, 63);
+            this.label66.Name = "label66";
+            this.label66.Size = new System.Drawing.Size(15, 13);
+            this.label66.TabIndex = 3;
+            this.label66.Text = "D";
+            // 
+            // ARSP2PTCH_I
+            // 
+            this.ARSP2PTCH_I.Location = new System.Drawing.Point(111, 36);
+            this.ARSP2PTCH_I.Name = "ARSP2PTCH_I";
+            this.ARSP2PTCH_I.Size = new System.Drawing.Size(78, 20);
+            this.ARSP2PTCH_I.TabIndex = 4;
+            // 
+            // label67
+            // 
+            this.label67.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label67.Location = new System.Drawing.Point(6, 40);
+            this.label67.Name = "label67";
+            this.label67.Size = new System.Drawing.Size(10, 13);
+            this.label67.TabIndex = 5;
+            this.label67.Text = "I";
+            // 
+            // ARSP2PTCH_P
+            // 
+            this.ARSP2PTCH_P.Location = new System.Drawing.Point(111, 13);
+            this.ARSP2PTCH_P.Name = "ARSP2PTCH_P";
+            this.ARSP2PTCH_P.Size = new System.Drawing.Size(78, 20);
+            this.ARSP2PTCH_P.TabIndex = 6;
+            // 
+            // label68
+            // 
+            this.label68.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label68.Location = new System.Drawing.Point(6, 17);
+            this.label68.Name = "label68";
+            this.label68.Size = new System.Drawing.Size(14, 13);
+            this.label68.TabIndex = 7;
+            this.label68.Text = "P";
+            // 
+            // groupBox11
+            // 
+            this.groupBox11.Controls.Add(this.HDNG2RLL_IMAX);
+            this.groupBox11.Controls.Add(this.label61);
+            this.groupBox11.Controls.Add(this.HDNG2RLL_D);
+            this.groupBox11.Controls.Add(this.label62);
+            this.groupBox11.Controls.Add(this.HDNG2RLL_I);
+            this.groupBox11.Controls.Add(this.label63);
+            this.groupBox11.Controls.Add(this.HDNG2RLL_P);
+            this.groupBox11.Controls.Add(this.label64);
+            this.groupBox11.Location = new System.Drawing.Point(12, 123);
+            this.groupBox11.Name = "groupBox11";
+            this.groupBox11.Size = new System.Drawing.Size(195, 108);
+            this.groupBox11.TabIndex = 20;
+            this.groupBox11.TabStop = false;
+            this.groupBox11.Text = "Nav Roll Pid";
+            // 
+            // HDNG2RLL_IMAX
+            // 
+            this.HDNG2RLL_IMAX.Location = new System.Drawing.Point(111, 82);
+            this.HDNG2RLL_IMAX.Name = "HDNG2RLL_IMAX";
+            this.HDNG2RLL_IMAX.Size = new System.Drawing.Size(78, 20);
+            this.HDNG2RLL_IMAX.TabIndex = 11;
+            // 
+            // label61
+            // 
+            this.label61.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label61.Location = new System.Drawing.Point(6, 86);
+            this.label61.Name = "label61";
+            this.label61.Size = new System.Drawing.Size(54, 13);
+            this.label61.TabIndex = 12;
+            this.label61.Text = "INT_MAX";
+            // 
+            // HDNG2RLL_D
+            // 
+            this.HDNG2RLL_D.Location = new System.Drawing.Point(111, 59);
+            this.HDNG2RLL_D.Name = "HDNG2RLL_D";
+            this.HDNG2RLL_D.Size = new System.Drawing.Size(78, 20);
+            this.HDNG2RLL_D.TabIndex = 9;
+            // 
+            // label62
+            // 
+            this.label62.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label62.Location = new System.Drawing.Point(6, 63);
+            this.label62.Name = "label62";
+            this.label62.Size = new System.Drawing.Size(15, 13);
+            this.label62.TabIndex = 13;
+            this.label62.Text = "D";
+            // 
+            // HDNG2RLL_I
+            // 
+            this.HDNG2RLL_I.Location = new System.Drawing.Point(111, 36);
+            this.HDNG2RLL_I.Name = "HDNG2RLL_I";
+            this.HDNG2RLL_I.Size = new System.Drawing.Size(78, 20);
+            this.HDNG2RLL_I.TabIndex = 7;
+            // 
+            // label63
+            // 
+            this.label63.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label63.Location = new System.Drawing.Point(6, 40);
+            this.label63.Name = "label63";
+            this.label63.Size = new System.Drawing.Size(10, 13);
+            this.label63.TabIndex = 14;
+            this.label63.Text = "I";
+            // 
+            // HDNG2RLL_P
+            // 
+            this.HDNG2RLL_P.Location = new System.Drawing.Point(111, 13);
+            this.HDNG2RLL_P.Name = "HDNG2RLL_P";
+            this.HDNG2RLL_P.Size = new System.Drawing.Size(78, 20);
+            this.HDNG2RLL_P.TabIndex = 5;
+            // 
+            // label64
+            // 
+            this.label64.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label64.Location = new System.Drawing.Point(6, 17);
+            this.label64.Name = "label64";
+            this.label64.Size = new System.Drawing.Size(14, 13);
+            this.label64.TabIndex = 15;
+            this.label64.Text = "P";
+            // 
+            // groupBox10
+            // 
+            this.groupBox10.Controls.Add(this.YW2SRV_IMAX);
+            this.groupBox10.Controls.Add(this.label57);
+            this.groupBox10.Controls.Add(this.YW2SRV_D);
+            this.groupBox10.Controls.Add(this.label58);
+            this.groupBox10.Controls.Add(this.YW2SRV_I);
+            this.groupBox10.Controls.Add(this.label59);
+            this.groupBox10.Controls.Add(this.YW2SRV_P);
+            this.groupBox10.Controls.Add(this.label60);
+            this.groupBox10.Location = new System.Drawing.Point(414, 15);
+            this.groupBox10.Name = "groupBox10";
+            this.groupBox10.Size = new System.Drawing.Size(195, 108);
+            this.groupBox10.TabIndex = 21;
+            this.groupBox10.TabStop = false;
+            this.groupBox10.Text = "Servo Yaw Pid";
+            // 
+            // YW2SRV_IMAX
+            // 
+            this.YW2SRV_IMAX.Location = new System.Drawing.Point(111, 82);
+            this.YW2SRV_IMAX.Name = "YW2SRV_IMAX";
+            this.YW2SRV_IMAX.Size = new System.Drawing.Size(78, 20);
+            this.YW2SRV_IMAX.TabIndex = 11;
+            // 
+            // label57
+            // 
+            this.label57.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label57.Location = new System.Drawing.Point(6, 86);
+            this.label57.Name = "label57";
+            this.label57.Size = new System.Drawing.Size(54, 13);
+            this.label57.TabIndex = 12;
+            this.label57.Text = "INT_MAX";
+            // 
+            // YW2SRV_D
+            // 
+            this.YW2SRV_D.Location = new System.Drawing.Point(111, 59);
+            this.YW2SRV_D.Name = "YW2SRV_D";
+            this.YW2SRV_D.Size = new System.Drawing.Size(78, 20);
+            this.YW2SRV_D.TabIndex = 9;
+            // 
+            // label58
+            // 
+            this.label58.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label58.Location = new System.Drawing.Point(6, 63);
+            this.label58.Name = "label58";
+            this.label58.Size = new System.Drawing.Size(15, 13);
+            this.label58.TabIndex = 13;
+            this.label58.Text = "D";
+            // 
+            // YW2SRV_I
+            // 
+            this.YW2SRV_I.Location = new System.Drawing.Point(111, 36);
+            this.YW2SRV_I.Name = "YW2SRV_I";
+            this.YW2SRV_I.Size = new System.Drawing.Size(78, 20);
+            this.YW2SRV_I.TabIndex = 7;
+            // 
+            // label59
+            // 
+            this.label59.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label59.Location = new System.Drawing.Point(6, 40);
+            this.label59.Name = "label59";
+            this.label59.Size = new System.Drawing.Size(10, 13);
+            this.label59.TabIndex = 14;
+            this.label59.Text = "I";
+            // 
+            // YW2SRV_P
+            // 
+            this.YW2SRV_P.Location = new System.Drawing.Point(111, 13);
+            this.YW2SRV_P.Name = "YW2SRV_P";
+            this.YW2SRV_P.Size = new System.Drawing.Size(78, 20);
+            this.YW2SRV_P.TabIndex = 5;
+            // 
+            // label60
+            // 
+            this.label60.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label60.Location = new System.Drawing.Point(6, 17);
+            this.label60.Name = "label60";
+            this.label60.Size = new System.Drawing.Size(14, 13);
+            this.label60.TabIndex = 15;
+            this.label60.Text = "P";
+            // 
+            // groupBox9
+            // 
+            this.groupBox9.Controls.Add(this.PTCH2SRV_IMAX);
+            this.groupBox9.Controls.Add(this.label53);
+            this.groupBox9.Controls.Add(this.PTCH2SRV_D);
+            this.groupBox9.Controls.Add(this.label54);
+            this.groupBox9.Controls.Add(this.PTCH2SRV_I);
+            this.groupBox9.Controls.Add(this.label55);
+            this.groupBox9.Controls.Add(this.PTCH2SRV_P);
+            this.groupBox9.Controls.Add(this.label56);
+            this.groupBox9.Location = new System.Drawing.Point(213, 15);
+            this.groupBox9.Name = "groupBox9";
+            this.groupBox9.Size = new System.Drawing.Size(195, 108);
+            this.groupBox9.TabIndex = 22;
+            this.groupBox9.TabStop = false;
+            this.groupBox9.Text = "Servo Pitch Pid";
+            // 
+            // PTCH2SRV_IMAX
+            // 
+            this.PTCH2SRV_IMAX.Location = new System.Drawing.Point(111, 82);
+            this.PTCH2SRV_IMAX.Name = "PTCH2SRV_IMAX";
+            this.PTCH2SRV_IMAX.Size = new System.Drawing.Size(78, 20);
+            this.PTCH2SRV_IMAX.TabIndex = 11;
+            // 
+            // label53
+            // 
+            this.label53.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label53.Location = new System.Drawing.Point(6, 86);
+            this.label53.Name = "label53";
+            this.label53.Size = new System.Drawing.Size(54, 13);
+            this.label53.TabIndex = 12;
+            this.label53.Text = "INT_MAX";
+            // 
+            // PTCH2SRV_D
+            // 
+            this.PTCH2SRV_D.Location = new System.Drawing.Point(111, 59);
+            this.PTCH2SRV_D.Name = "PTCH2SRV_D";
+            this.PTCH2SRV_D.Size = new System.Drawing.Size(78, 20);
+            this.PTCH2SRV_D.TabIndex = 9;
+            // 
+            // label54
+            // 
+            this.label54.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label54.Location = new System.Drawing.Point(6, 63);
+            this.label54.Name = "label54";
+            this.label54.Size = new System.Drawing.Size(15, 13);
+            this.label54.TabIndex = 13;
+            this.label54.Text = "D";
+            // 
+            // PTCH2SRV_I
+            // 
+            this.PTCH2SRV_I.Location = new System.Drawing.Point(111, 36);
+            this.PTCH2SRV_I.Name = "PTCH2SRV_I";
+            this.PTCH2SRV_I.Size = new System.Drawing.Size(78, 20);
+            this.PTCH2SRV_I.TabIndex = 7;
+            // 
+            // label55
+            // 
+            this.label55.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label55.Location = new System.Drawing.Point(6, 40);
+            this.label55.Name = "label55";
+            this.label55.Size = new System.Drawing.Size(10, 13);
+            this.label55.TabIndex = 14;
+            this.label55.Text = "I";
+            // 
+            // PTCH2SRV_P
+            // 
+            this.PTCH2SRV_P.Location = new System.Drawing.Point(111, 13);
+            this.PTCH2SRV_P.Name = "PTCH2SRV_P";
+            this.PTCH2SRV_P.Size = new System.Drawing.Size(78, 20);
+            this.PTCH2SRV_P.TabIndex = 5;
+            // 
+            // label56
+            // 
+            this.label56.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label56.Location = new System.Drawing.Point(6, 17);
+            this.label56.Name = "label56";
+            this.label56.Size = new System.Drawing.Size(14, 13);
+            this.label56.TabIndex = 15;
+            this.label56.Text = "P";
+            // 
+            // groupBox8
+            // 
+            this.groupBox8.Controls.Add(this.RLL2SRV_IMAX);
+            this.groupBox8.Controls.Add(this.label49);
+            this.groupBox8.Controls.Add(this.RLL2SRV_D);
+            this.groupBox8.Controls.Add(this.label50);
+            this.groupBox8.Controls.Add(this.RLL2SRV_I);
+            this.groupBox8.Controls.Add(this.label51);
+            this.groupBox8.Controls.Add(this.RLL2SRV_P);
+            this.groupBox8.Controls.Add(this.label52);
+            this.groupBox8.Location = new System.Drawing.Point(12, 15);
+            this.groupBox8.Name = "groupBox8";
+            this.groupBox8.Size = new System.Drawing.Size(195, 108);
+            this.groupBox8.TabIndex = 23;
+            this.groupBox8.TabStop = false;
+            this.groupBox8.Text = "Servo Roll Pid";
+            // 
+            // RLL2SRV_IMAX
+            // 
+            this.RLL2SRV_IMAX.Location = new System.Drawing.Point(111, 82);
+            this.RLL2SRV_IMAX.Name = "RLL2SRV_IMAX";
+            this.RLL2SRV_IMAX.Size = new System.Drawing.Size(78, 20);
+            this.RLL2SRV_IMAX.TabIndex = 11;
+            // 
+            // label49
+            // 
+            this.label49.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label49.Location = new System.Drawing.Point(6, 86);
+            this.label49.Name = "label49";
+            this.label49.Size = new System.Drawing.Size(54, 13);
+            this.label49.TabIndex = 12;
+            this.label49.Text = "INT_MAX";
+            // 
+            // RLL2SRV_D
+            // 
+            this.RLL2SRV_D.Location = new System.Drawing.Point(111, 59);
+            this.RLL2SRV_D.Name = "RLL2SRV_D";
+            this.RLL2SRV_D.Size = new System.Drawing.Size(78, 20);
+            this.RLL2SRV_D.TabIndex = 9;
+            // 
+            // label50
+            // 
+            this.label50.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label50.Location = new System.Drawing.Point(6, 63);
+            this.label50.Name = "label50";
+            this.label50.Size = new System.Drawing.Size(15, 13);
+            this.label50.TabIndex = 13;
+            this.label50.Text = "D";
+            // 
+            // RLL2SRV_I
+            // 
+            this.RLL2SRV_I.Location = new System.Drawing.Point(111, 36);
+            this.RLL2SRV_I.Name = "RLL2SRV_I";
+            this.RLL2SRV_I.Size = new System.Drawing.Size(78, 20);
+            this.RLL2SRV_I.TabIndex = 7;
+            // 
+            // label51
+            // 
+            this.label51.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label51.Location = new System.Drawing.Point(6, 40);
+            this.label51.Name = "label51";
+            this.label51.Size = new System.Drawing.Size(10, 13);
+            this.label51.TabIndex = 14;
+            this.label51.Text = "I";
+            // 
+            // RLL2SRV_P
+            // 
+            this.RLL2SRV_P.Location = new System.Drawing.Point(111, 13);
+            this.RLL2SRV_P.Name = "RLL2SRV_P";
+            this.RLL2SRV_P.Size = new System.Drawing.Size(78, 20);
+            this.RLL2SRV_P.TabIndex = 5;
+            // 
+            // label52
+            // 
+            this.label52.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label52.Location = new System.Drawing.Point(6, 17);
+            this.label52.Name = "label52";
+            this.label52.Size = new System.Drawing.Size(14, 13);
+            this.label52.TabIndex = 15;
+            this.label52.Text = "P";
+            // 
+            // ConfigArduplane
+            // 
+            this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
+            this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+            this.Controls.Add(this.groupBox3);
+            this.Controls.Add(this.groupBox1);
+            this.Controls.Add(this.groupBox2);
+            this.Controls.Add(this.groupBox15);
+            this.Controls.Add(this.groupBox16);
+            this.Controls.Add(this.groupBox14);
+            this.Controls.Add(this.groupBox13);
+            this.Controls.Add(this.groupBox12);
+            this.Controls.Add(this.groupBox11);
+            this.Controls.Add(this.groupBox10);
+            this.Controls.Add(this.groupBox9);
+            this.Controls.Add(this.groupBox8);
+            this.Name = "ConfigArduplane";
+            this.Size = new System.Drawing.Size(621, 456);
+            this.Load += new System.EventHandler(this.ConfigArduplane_Load);
+            this.groupBox3.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.THR_FS_VALUE)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.THR_MAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.THR_MIN)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.TRIM_THROTTLE)).EndInit();
+            this.groupBox1.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.ARSPD_RATIO)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ARSPD_FBW_MIN)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.TRIM_ARSPD_CM)).EndInit();
+            this.groupBox2.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MIN)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.LIM_PITCH_MAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.LIM_ROLL_CD)).EndInit();
+            this.groupBox15.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.XTRK_ANGLE_CD)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.XTRK_GAIN_SC)).EndInit();
+            this.groupBox16.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.KFF_PTCH2THR)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.KFF_RDDRMIX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.KFF_PTCHCOMP)).EndInit();
+            this.groupBox14.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_IMAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_D)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_I)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ENRGY2THR_P)).EndInit();
+            this.groupBox13.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_IMAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_D)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_I)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ALT2PTCH_P)).EndInit();
+            this.groupBox12.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_IMAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_D)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_I)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.ARSP2PTCH_P)).EndInit();
+            this.groupBox11.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_IMAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_D)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_I)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.HDNG2RLL_P)).EndInit();
+            this.groupBox10.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_IMAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_D)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_I)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.YW2SRV_P)).EndInit();
+            this.groupBox9.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_IMAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_D)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_I)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.PTCH2SRV_P)).EndInit();
+            this.groupBox8.ResumeLayout(false);
+            ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_IMAX)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_D)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_I)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_P)).EndInit();
+            this.ResumeLayout(false);
+
+        }
+
+        #endregion
+
+        private System.Windows.Forms.GroupBox groupBox3;
+        private System.Windows.Forms.NumericUpDown THR_FS_VALUE;
+        private System.Windows.Forms.Label label5;
+        private System.Windows.Forms.NumericUpDown THR_MAX;
+        private System.Windows.Forms.Label label6;
+        private System.Windows.Forms.NumericUpDown THR_MIN;
+        private System.Windows.Forms.Label label7;
+        private System.Windows.Forms.NumericUpDown TRIM_THROTTLE;
+        private System.Windows.Forms.Label label8;
+        private System.Windows.Forms.GroupBox groupBox1;
+        private System.Windows.Forms.NumericUpDown ARSPD_RATIO;
+        private System.Windows.Forms.Label label1;
+        private System.Windows.Forms.NumericUpDown ARSPD_FBW_MAX;
+        private System.Windows.Forms.Label label2;
+        private System.Windows.Forms.NumericUpDown ARSPD_FBW_MIN;
+        private System.Windows.Forms.Label label3;
+        private System.Windows.Forms.NumericUpDown TRIM_ARSPD_CM;
+        private System.Windows.Forms.Label label4;
+        private System.Windows.Forms.GroupBox groupBox2;
+        private System.Windows.Forms.NumericUpDown LIM_PITCH_MIN;
+        private System.Windows.Forms.Label label39;
+        private System.Windows.Forms.NumericUpDown LIM_PITCH_MAX;
+        private System.Windows.Forms.Label label38;
+        private System.Windows.Forms.NumericUpDown LIM_ROLL_CD;
+        private System.Windows.Forms.Label label37;
+        private System.Windows.Forms.GroupBox groupBox15;
+        private System.Windows.Forms.NumericUpDown XTRK_ANGLE_CD;
+        private System.Windows.Forms.Label label79;
+        private System.Windows.Forms.NumericUpDown XTRK_GAIN_SC;
+        private System.Windows.Forms.Label label80;
+        private System.Windows.Forms.GroupBox groupBox16;
+        private System.Windows.Forms.NumericUpDown KFF_PTCH2THR;
+        private System.Windows.Forms.Label label83;
+        private System.Windows.Forms.NumericUpDown KFF_RDDRMIX;
+        private System.Windows.Forms.Label label78;
+        private System.Windows.Forms.NumericUpDown KFF_PTCHCOMP;
+        private System.Windows.Forms.Label label81;
+        private System.Windows.Forms.GroupBox groupBox14;
+        private System.Windows.Forms.NumericUpDown ENRGY2THR_IMAX;
+        private System.Windows.Forms.Label label73;
+        private System.Windows.Forms.NumericUpDown ENRGY2THR_D;
+        private System.Windows.Forms.Label label74;
+        private System.Windows.Forms.NumericUpDown ENRGY2THR_I;
+        private System.Windows.Forms.Label label75;
+        private System.Windows.Forms.NumericUpDown ENRGY2THR_P;
+        private System.Windows.Forms.Label label76;
+        private System.Windows.Forms.GroupBox groupBox13;
+        private System.Windows.Forms.NumericUpDown ALT2PTCH_IMAX;
+        private System.Windows.Forms.Label label69;
+        private System.Windows.Forms.NumericUpDown ALT2PTCH_D;
+        private System.Windows.Forms.Label label70;
+        private System.Windows.Forms.NumericUpDown ALT2PTCH_I;
+        private System.Windows.Forms.Label label71;
+        private System.Windows.Forms.NumericUpDown ALT2PTCH_P;
+        private System.Windows.Forms.Label label72;
+        private System.Windows.Forms.GroupBox groupBox12;
+        private System.Windows.Forms.NumericUpDown ARSP2PTCH_IMAX;
+        private System.Windows.Forms.Label label65;
+        private System.Windows.Forms.NumericUpDown ARSP2PTCH_D;
+        private System.Windows.Forms.Label label66;
+        private System.Windows.Forms.NumericUpDown ARSP2PTCH_I;
+        private System.Windows.Forms.Label label67;
+        private System.Windows.Forms.NumericUpDown ARSP2PTCH_P;
+        private System.Windows.Forms.Label label68;
+        private System.Windows.Forms.GroupBox groupBox11;
+        private System.Windows.Forms.NumericUpDown HDNG2RLL_IMAX;
+        private System.Windows.Forms.Label label61;
+        private System.Windows.Forms.NumericUpDown HDNG2RLL_D;
+        private System.Windows.Forms.Label label62;
+        private System.Windows.Forms.NumericUpDown HDNG2RLL_I;
+        private System.Windows.Forms.Label label63;
+        private System.Windows.Forms.NumericUpDown HDNG2RLL_P;
+        private System.Windows.Forms.Label label64;
+        private System.Windows.Forms.GroupBox groupBox10;
+        private System.Windows.Forms.NumericUpDown YW2SRV_IMAX;
+        private System.Windows.Forms.Label label57;
+        private System.Windows.Forms.NumericUpDown YW2SRV_D;
+        private System.Windows.Forms.Label label58;
+        private System.Windows.Forms.NumericUpDown YW2SRV_I;
+        private System.Windows.Forms.Label label59;
+        private System.Windows.Forms.NumericUpDown YW2SRV_P;
+        private System.Windows.Forms.Label label60;
+        private System.Windows.Forms.GroupBox groupBox9;
+        private System.Windows.Forms.NumericUpDown PTCH2SRV_IMAX;
+        private System.Windows.Forms.Label label53;
+        private System.Windows.Forms.NumericUpDown PTCH2SRV_D;
+        private System.Windows.Forms.Label label54;
+        private System.Windows.Forms.NumericUpDown PTCH2SRV_I;
+        private System.Windows.Forms.Label label55;
+        private System.Windows.Forms.NumericUpDown PTCH2SRV_P;
+        private System.Windows.Forms.Label label56;
+        private System.Windows.Forms.GroupBox groupBox8;
+        private System.Windows.Forms.NumericUpDown RLL2SRV_IMAX;
+        private System.Windows.Forms.Label label49;
+        private System.Windows.Forms.NumericUpDown RLL2SRV_D;
+        private System.Windows.Forms.Label label50;
+        private System.Windows.Forms.NumericUpDown RLL2SRV_I;
+        private System.Windows.Forms.Label label51;
+        private System.Windows.Forms.NumericUpDown RLL2SRV_P;
+        private System.Windows.Forms.Label label52;
+        private System.Windows.Forms.ToolTip toolTip1;
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs
new file mode 100644
index 0000000000000000000000000000000000000000..34afb1dc4c35063fa6fffebe77091856f654c93d
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs
@@ -0,0 +1,271 @@
+using System;
+using System.Collections.Generic;
+using System.ComponentModel;
+using System.Drawing;
+using System.Data;
+using System.Linq;
+using System.Text;
+using System.Windows.Forms;
+using ArdupilotMega.Controls.BackstageView;
+using System.Collections;
+
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    public partial class ConfigArduplane : BackStageViewContentPanel
+    {
+        Hashtable changes = new Hashtable();
+        static Hashtable tooltips = new Hashtable();
+        internal bool startup = true;
+
+        public ConfigArduplane()
+        {
+            InitializeComponent();
+        }
+
+        private void ConfigArduplane_Load(object sender, EventArgs e)
+        {
+            if (!MainV2.comPort.BaseStream.IsOpen)
+            {
+                this.Enabled = false;
+                return;
+            }
+            else
+            {
+                if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
+                {
+                    this.Enabled = true;
+                }
+                else
+                {
+                    this.Enabled = false;
+                    return;
+                }
+            }
+
+            startup = true;
+
+            changes.Clear();
+
+            // read tooltips
+            if (tooltips.Count == 0)
+                readToolTips();
+
+            processToScreen();
+
+            startup = false;
+        }
+
+        public struct paramsettings // hk's
+        {
+            public string name;
+            public float minvalue;
+            public float maxvalue;
+            public float normalvalue;
+            public float scale;
+            public string desc;
+        }
+
+        void readToolTips()
+        {
+            System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Configuration));
+
+            string data = resources.GetString("MAVParam");
+
+            if (data == null)
+            {
+                data = global::ArdupilotMega.Properties.Resources.MAVParam;
+            }
+
+            string[] tips = data.Split(new char[] { '\r', '\n' }, StringSplitOptions.RemoveEmptyEntries);
+
+            foreach (var tip in tips)
+            {
+                if (!tip.StartsWith("||"))
+                    continue;
+
+                string[] cols = tip.Split(new string[] { "||" }, 9, StringSplitOptions.None);
+
+                if (cols.Length >= 8)
+                {
+                    paramsettings param = new paramsettings();
+                    try
+                    {
+                        param.name = cols[1];
+                        param.desc = AddNewLinesForTooltip(cols[7]);
+                        param.scale = float.Parse(cols[5]);
+                        param.minvalue = float.Parse(cols[2]);
+                        param.maxvalue = float.Parse(cols[3]);
+                        param.normalvalue = float.Parse(cols[4]);
+                    }
+                    catch { }
+                    tooltips[cols[1]] = param;
+                }
+
+            }
+        }
+
+
+        // from http://stackoverflow.com/questions/2512781/winforms-big-paragraph-tooltip/2512895#2512895
+        private const int maximumSingleLineTooltipLength = 50;
+
+        private static string AddNewLinesForTooltip(string text)
+        {
+            if (text.Length < maximumSingleLineTooltipLength)
+                return text;
+            int lineLength = (int)Math.Sqrt((double)text.Length) * 2;
+            StringBuilder sb = new StringBuilder();
+            int currentLinePosition = 0;
+            for (int textIndex = 0; textIndex < text.Length; textIndex++)
+            {
+                // If we have reached the target line length and the next      
+                // character is whitespace then begin a new line.   
+                if (currentLinePosition >= lineLength &&
+                    char.IsWhiteSpace(text[textIndex]))
+                {
+                    sb.Append(Environment.NewLine);
+                    currentLinePosition = 0;
+                }
+                // If we have just started a new line, skip all the whitespace.    
+                if (currentLinePosition == 0)
+                    while (textIndex < text.Length && char.IsWhiteSpace(text[textIndex]))
+                        textIndex++;
+                // Append the next character.     
+                if (textIndex < text.Length) sb.Append(text[textIndex]);
+                currentLinePosition++;
+            }
+            return sb.ToString();
+        }
+
+        void disableNumericUpDownControls(Control inctl)
+        {
+            foreach (Control ctl in inctl.Controls)
+            {
+                if (ctl.Controls.Count > 0)
+                {
+                    disableNumericUpDownControls(ctl);
+                }
+                if (ctl.GetType() == typeof(NumericUpDown))
+                {
+                    ctl.Enabled = false;
+                }
+            }
+        }
+
+        internal void processToScreen()
+        {
+            toolTip1.RemoveAll();
+
+            disableNumericUpDownControls(this);
+
+            // process hashdefines and update display
+            foreach (string value in MainV2.comPort.param.Keys)
+            {
+                if (value == null || value == "")
+                    continue;
+
+                string name = value;
+                Control[] text = this.Controls.Find(name, true);
+                foreach (Control ctl in text)
+                {
+                    try
+                    {
+                        if (ctl.GetType() == typeof(NumericUpDown))
+                        {
+
+                            NumericUpDown thisctl = ((NumericUpDown)ctl);
+                            thisctl.Maximum = 9000;
+                            thisctl.Minimum = -9000;
+                            thisctl.Value = (decimal)(float)MainV2.comPort.param[value];
+                            thisctl.Increment = (decimal)0.001;
+                            if (thisctl.Name.EndsWith("_P") || thisctl.Name.EndsWith("_I") || thisctl.Name.EndsWith("_D")
+                                || thisctl.Name.EndsWith("_LOW") || thisctl.Name.EndsWith("_HIGH") || thisctl.Value == 0
+                                || thisctl.Value.ToString("0.###", new System.Globalization.CultureInfo("en-US")).Contains("."))
+                            {
+                                thisctl.DecimalPlaces = 3;
+                            }
+                            else
+                            {
+                                thisctl.Increment = (decimal)1;
+                                thisctl.DecimalPlaces = 1;
+                            }
+
+                            if (thisctl.Name.EndsWith("_IMAX"))
+                            {
+                                thisctl.Maximum = 180;
+                                thisctl.Minimum = -180;
+                            }
+
+                            thisctl.Enabled = true;
+
+                            thisctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
+                            thisctl.Validated += null;
+                            if (tooltips[value] != null)
+                            {
+                                try
+                                {
+                                    toolTip1.SetToolTip(ctl, ((paramsettings)tooltips[value]).desc);
+                                }
+                                catch { }
+                            }
+                            thisctl.Validated += new EventHandler(EEPROM_View_float_TextChanged);
+
+                        }
+                        else if (ctl.GetType() == typeof(ComboBox))
+                        {
+
+                            ComboBox thisctl = ((ComboBox)ctl);
+
+                            thisctl.SelectedIndex = (int)(float)MainV2.comPort.param[value];
+
+                            thisctl.Validated += new EventHandler(ComboBox_Validated);
+                        }
+                    }
+                    catch { }
+
+                }
+                if (text.Length == 0)
+                {
+                    //Console.WriteLine(name + " not found");
+                }
+
+            }
+        }
+
+        void ComboBox_Validated(object sender, EventArgs e)
+        {
+            EEPROM_View_float_TextChanged(sender, e);
+        }
+
+        void Configuration_Validating(object sender, CancelEventArgs e)
+        {
+            EEPROM_View_float_TextChanged(sender, e);
+        }
+
+        internal void EEPROM_View_float_TextChanged(object sender, EventArgs e)
+        {
+            float value = 0;
+            string name = ((Control)sender).Name;
+
+            // do domainupdown state check
+            try
+            {
+                if (sender.GetType() == typeof(NumericUpDown))
+                {
+                    value = float.Parse(((Control)sender).Text);
+                    changes[name] = value;
+                }
+                else if (sender.GetType() == typeof(ComboBox))
+                {
+                    value = ((ComboBox)sender).SelectedIndex;
+                    changes[name] = value;
+                }
+                ((Control)sender).BackColor = Color.Green;
+            }
+            catch (Exception)
+            {
+                ((Control)sender).BackColor = Color.Red;
+            }         
+        }
+
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.resx
new file mode 100644
index 0000000000000000000000000000000000000000..271670364af059e95ad645d78fad7553ecbd0d09
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.resx
@@ -0,0 +1,123 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
+    <value>17, 17</value>
+  </metadata>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs
new file mode 100644
index 0000000000000000000000000000000000000000..0c3c2c5a7b8d2f1e0f203dd281d9b73c1c05e13d
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs
@@ -0,0 +1,230 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    partial class ConfigBatteryMonitoring
+    {
+        /// <summary> 
+        /// Required designer variable.
+        /// </summary>
+        private System.ComponentModel.IContainer components = null;
+
+        /// <summary> 
+        /// Clean up any resources being used.
+        /// </summary>
+        /// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
+        protected override void Dispose(bool disposing)
+        {
+            if (disposing && (components != null))
+            {
+                components.Dispose();
+            }
+            base.Dispose(disposing);
+        }
+
+        #region Component Designer generated code
+
+        /// <summary> 
+        /// Required method for Designer support - do not modify 
+        /// the contents of this method with the code editor.
+        /// </summary>
+        private void InitializeComponent()
+        {
+            System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigBatteryMonitoring));
+            this.groupBox4 = new System.Windows.Forms.GroupBox();
+            this.label31 = new System.Windows.Forms.Label();
+            this.label32 = new System.Windows.Forms.Label();
+            this.label33 = new System.Windows.Forms.Label();
+            this.TXT_ampspervolt = new System.Windows.Forms.TextBox();
+            this.label34 = new System.Windows.Forms.Label();
+            this.TXT_divider = new System.Windows.Forms.TextBox();
+            this.label35 = new System.Windows.Forms.Label();
+            this.TXT_voltage = new System.Windows.Forms.TextBox();
+            this.TXT_inputvoltage = new System.Windows.Forms.TextBox();
+            this.TXT_measuredvoltage = new System.Windows.Forms.TextBox();
+            this.label47 = new System.Windows.Forms.Label();
+            this.CMB_batmonsensortype = new System.Windows.Forms.ComboBox();
+            this.textBox3 = new System.Windows.Forms.TextBox();
+            this.label29 = new System.Windows.Forms.Label();
+            this.label30 = new System.Windows.Forms.Label();
+            this.TXT_battcapacity = new System.Windows.Forms.TextBox();
+            this.CMB_batmontype = new System.Windows.Forms.ComboBox();
+            this.pictureBox5 = new System.Windows.Forms.PictureBox();
+            this.groupBox4.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.pictureBox5)).BeginInit();
+            this.SuspendLayout();
+            // 
+            // groupBox4
+            // 
+            this.groupBox4.Controls.Add(this.label31);
+            this.groupBox4.Controls.Add(this.label32);
+            this.groupBox4.Controls.Add(this.label33);
+            this.groupBox4.Controls.Add(this.TXT_ampspervolt);
+            this.groupBox4.Controls.Add(this.label34);
+            this.groupBox4.Controls.Add(this.TXT_divider);
+            this.groupBox4.Controls.Add(this.label35);
+            this.groupBox4.Controls.Add(this.TXT_voltage);
+            this.groupBox4.Controls.Add(this.TXT_inputvoltage);
+            this.groupBox4.Controls.Add(this.TXT_measuredvoltage);
+            resources.ApplyResources(this.groupBox4, "groupBox4");
+            this.groupBox4.Name = "groupBox4";
+            this.groupBox4.TabStop = false;
+            // 
+            // label31
+            // 
+            resources.ApplyResources(this.label31, "label31");
+            this.label31.Name = "label31";
+            // 
+            // label32
+            // 
+            resources.ApplyResources(this.label32, "label32");
+            this.label32.Name = "label32";
+            // 
+            // label33
+            // 
+            resources.ApplyResources(this.label33, "label33");
+            this.label33.Name = "label33";
+            // 
+            // TXT_ampspervolt
+            // 
+            resources.ApplyResources(this.TXT_ampspervolt, "TXT_ampspervolt");
+            this.TXT_ampspervolt.Name = "TXT_ampspervolt";
+            this.TXT_ampspervolt.Validated += new System.EventHandler(this.TXT_ampspervolt_Validated);
+            // 
+            // label34
+            // 
+            resources.ApplyResources(this.label34, "label34");
+            this.label34.Name = "label34";
+            // 
+            // TXT_divider
+            // 
+            resources.ApplyResources(this.TXT_divider, "TXT_divider");
+            this.TXT_divider.Name = "TXT_divider";
+            this.TXT_divider.Validated += new System.EventHandler(this.TXT_divider_Validated);
+            // 
+            // label35
+            // 
+            resources.ApplyResources(this.label35, "label35");
+            this.label35.Name = "label35";
+            // 
+            // TXT_voltage
+            // 
+            resources.ApplyResources(this.TXT_voltage, "TXT_voltage");
+            this.TXT_voltage.Name = "TXT_voltage";
+            this.TXT_voltage.ReadOnly = true;
+            // 
+            // TXT_inputvoltage
+            // 
+            resources.ApplyResources(this.TXT_inputvoltage, "TXT_inputvoltage");
+            this.TXT_inputvoltage.Name = "TXT_inputvoltage";
+            this.TXT_inputvoltage.Validated += new System.EventHandler(this.TXT_inputvoltage_Validated);
+            // 
+            // TXT_measuredvoltage
+            // 
+            resources.ApplyResources(this.TXT_measuredvoltage, "TXT_measuredvoltage");
+            this.TXT_measuredvoltage.Name = "TXT_measuredvoltage";
+            this.TXT_measuredvoltage.Validated += new System.EventHandler(this.TXT_measuredvoltage_Validated);
+            // 
+            // label47
+            // 
+            resources.ApplyResources(this.label47, "label47");
+            this.label47.Name = "label47";
+            // 
+            // CMB_batmonsensortype
+            // 
+            this.CMB_batmonsensortype.FormattingEnabled = true;
+            this.CMB_batmonsensortype.Items.AddRange(new object[] {
+            resources.GetString("CMB_batmonsensortype.Items"),
+            resources.GetString("CMB_batmonsensortype.Items1"),
+            resources.GetString("CMB_batmonsensortype.Items2"),
+            resources.GetString("CMB_batmonsensortype.Items3")});
+            resources.ApplyResources(this.CMB_batmonsensortype, "CMB_batmonsensortype");
+            this.CMB_batmonsensortype.Name = "CMB_batmonsensortype";
+            this.CMB_batmonsensortype.SelectedIndexChanged += new System.EventHandler(this.CMB_batmonsensortype_SelectedIndexChanged);
+            // 
+            // textBox3
+            // 
+            resources.ApplyResources(this.textBox3, "textBox3");
+            this.textBox3.Name = "textBox3";
+            this.textBox3.ReadOnly = true;
+            // 
+            // label29
+            // 
+            resources.ApplyResources(this.label29, "label29");
+            this.label29.Name = "label29";
+            // 
+            // label30
+            // 
+            resources.ApplyResources(this.label30, "label30");
+            this.label30.Name = "label30";
+            // 
+            // TXT_battcapacity
+            // 
+            resources.ApplyResources(this.TXT_battcapacity, "TXT_battcapacity");
+            this.TXT_battcapacity.Name = "TXT_battcapacity";
+            this.TXT_battcapacity.Validated += new System.EventHandler(this.TXT_battcapacity_Validated);
+            // 
+            // CMB_batmontype
+            // 
+            this.CMB_batmontype.FormattingEnabled = true;
+            this.CMB_batmontype.Items.AddRange(new object[] {
+            resources.GetString("CMB_batmontype.Items"),
+            resources.GetString("CMB_batmontype.Items1"),
+            resources.GetString("CMB_batmontype.Items2")});
+            resources.ApplyResources(this.CMB_batmontype, "CMB_batmontype");
+            this.CMB_batmontype.Name = "CMB_batmontype";
+            this.CMB_batmontype.SelectedIndexChanged += new System.EventHandler(this.CMB_batmontype_SelectedIndexChanged);
+            // 
+            // pictureBox5
+            // 
+            this.pictureBox5.BackColor = System.Drawing.Color.White;
+            this.pictureBox5.BackgroundImage = global::ArdupilotMega.Properties.Resources.attocurrent;
+            resources.ApplyResources(this.pictureBox5, "pictureBox5");
+            this.pictureBox5.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle;
+            this.pictureBox5.Name = "pictureBox5";
+            this.pictureBox5.TabStop = false;
+            // 
+            // ConfigBatteryMonitoring
+            // 
+            resources.ApplyResources(this, "$this");
+            this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+            this.Controls.Add(this.groupBox4);
+            this.Controls.Add(this.label47);
+            this.Controls.Add(this.CMB_batmonsensortype);
+            this.Controls.Add(this.textBox3);
+            this.Controls.Add(this.label29);
+            this.Controls.Add(this.label30);
+            this.Controls.Add(this.TXT_battcapacity);
+            this.Controls.Add(this.CMB_batmontype);
+            this.Controls.Add(this.pictureBox5);
+            this.Name = "ConfigBatteryMonitoring";
+            this.Load += new System.EventHandler(this.ConfigBatteryMonitoring_Load);
+            this.groupBox4.ResumeLayout(false);
+            this.groupBox4.PerformLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.pictureBox5)).EndInit();
+            this.ResumeLayout(false);
+            this.PerformLayout();
+
+        }
+
+        #endregion
+
+        private System.Windows.Forms.GroupBox groupBox4;
+        private System.Windows.Forms.Label label31;
+        private System.Windows.Forms.Label label32;
+        private System.Windows.Forms.Label label33;
+        private System.Windows.Forms.TextBox TXT_ampspervolt;
+        private System.Windows.Forms.Label label34;
+        private System.Windows.Forms.TextBox TXT_divider;
+        private System.Windows.Forms.Label label35;
+        private System.Windows.Forms.TextBox TXT_voltage;
+        private System.Windows.Forms.TextBox TXT_inputvoltage;
+        private System.Windows.Forms.TextBox TXT_measuredvoltage;
+        private System.Windows.Forms.Label label47;
+        private System.Windows.Forms.ComboBox CMB_batmonsensortype;
+        private System.Windows.Forms.TextBox textBox3;
+        private System.Windows.Forms.Label label29;
+        private System.Windows.Forms.Label label30;
+        private System.Windows.Forms.TextBox TXT_battcapacity;
+        private System.Windows.Forms.ComboBox CMB_batmontype;
+        private System.Windows.Forms.PictureBox pictureBox5;
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs
new file mode 100644
index 0000000000000000000000000000000000000000..d84fe9af39df8d0d32c21866fa1c9ecf778bf370
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs
@@ -0,0 +1,362 @@
+using System;
+using System.Collections.Generic;
+using System.ComponentModel;
+using System.Drawing;
+using System.Data;
+using System.Linq;
+using System.Text;
+using System.Windows.Forms;
+using ArdupilotMega.Controls.BackstageView;
+
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    public partial class ConfigBatteryMonitoring : BackStageViewContentPanel
+    {
+        bool startup = false;
+
+        public ConfigBatteryMonitoring()
+        {
+            InitializeComponent();
+        }
+
+        private void CHK_enablebattmon_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            try
+            {
+                if (((CheckBox)sender).Checked == false)
+                {
+                    CMB_batmontype.SelectedIndex = 0;
+                }
+                else
+                {
+                    if (CMB_batmontype.SelectedIndex <= 0)
+                        CMB_batmontype.SelectedIndex = 1;
+                }
+            }
+            catch { CustomMessageBox.Show("Set BATT_MONITOR Failed"); }
+        }
+        private void TXT_battcapacity_Validating(object sender, CancelEventArgs e)
+        {
+            float ans = 0;
+            e.Cancel = !float.TryParse(TXT_battcapacity.Text, out ans);
+        }
+        private void TXT_battcapacity_Validated(object sender, EventArgs e)
+        {
+            if (startup || ((TextBox)sender).Enabled == false)
+                return;
+            try
+            {
+                if (MainV2.comPort.param["BATT_CAPACITY"] == null)
+                {
+                    CustomMessageBox.Show("Not Available");
+                }
+                else
+                {
+                    MainV2.comPort.setParam("BATT_CAPACITY", float.Parse(TXT_battcapacity.Text));
+                }
+            }
+            catch { CustomMessageBox.Show("Set BATT_CAPACITY Failed"); }
+        }
+        private void CMB_batmontype_SelectedIndexChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            try
+            {
+                if (MainV2.comPort.param["BATT_MONITOR"] == null)
+                {
+                    CustomMessageBox.Show("Not Available");
+                }
+                else
+                {
+                    int selection = int.Parse(CMB_batmontype.Text.Substring(0, 1));
+
+                    CMB_batmonsensortype.Enabled = true;
+
+                    TXT_voltage.Enabled = false;
+
+                    if (selection == 0)
+                    {
+                        CMB_batmonsensortype.Enabled = false;
+                        groupBox4.Enabled = false;
+                    }
+                    else if (selection == 4)
+                    {
+                        CMB_batmonsensortype.Enabled = true;
+                        groupBox4.Enabled = true;
+                        TXT_ampspervolt.Enabled = true;
+                    }
+                    else if (selection == 3)
+                    {
+                        groupBox4.Enabled = true;
+                        CMB_batmonsensortype.Enabled = false;
+                        TXT_ampspervolt.Enabled = false;
+                        TXT_inputvoltage.Enabled = true;
+                        TXT_measuredvoltage.Enabled = true;
+                        TXT_divider.Enabled = true;
+                    }
+
+                    MainV2.comPort.setParam("BATT_MONITOR", selection);
+                }
+            }
+            catch { CustomMessageBox.Show("Set BATT_MONITOR Failed"); }
+        }
+        private void TXT_inputvoltage_Validating(object sender, CancelEventArgs e)
+        {
+            float ans = 0;
+            e.Cancel = !float.TryParse(TXT_inputvoltage.Text, out ans);
+        }
+        private void TXT_inputvoltage_Validated(object sender, EventArgs e)
+        {
+            if (startup || ((TextBox)sender).Enabled == false)
+                return;
+            try
+            {
+                if (MainV2.comPort.param["INPUT_VOLTS"] == null)
+                {
+                    CustomMessageBox.Show("Not Available");
+                }
+                else
+                {
+                    MainV2.comPort.setParam("INPUT_VOLTS", float.Parse(TXT_inputvoltage.Text));
+                }
+            }
+            catch { CustomMessageBox.Show("Set INPUT_VOLTS Failed"); }
+        }
+        private void TXT_measuredvoltage_Validating(object sender, CancelEventArgs e)
+        {
+            float ans = 0;
+            e.Cancel = !float.TryParse(TXT_measuredvoltage.Text, out ans);
+        }
+        private void TXT_measuredvoltage_Validated(object sender, EventArgs e)
+        {
+            if (startup || ((TextBox)sender).Enabled == false)
+                return;
+            try
+            {
+                float measuredvoltage = float.Parse(TXT_measuredvoltage.Text);
+                float voltage = float.Parse(TXT_voltage.Text);
+                float divider = float.Parse(TXT_divider.Text);
+                if (voltage == 0)
+                    return;
+                float new_divider = (measuredvoltage * divider) / voltage;
+                TXT_divider.Text = new_divider.ToString();
+            }
+            catch { CustomMessageBox.Show("Invalid number entered"); return; }
+
+            try
+            {
+                if (MainV2.comPort.param["VOLT_DIVIDER"] == null)
+                {
+                    CustomMessageBox.Show("Not Available");
+                }
+                else
+                {
+                    MainV2.comPort.setParam("VOLT_DIVIDER", float.Parse(TXT_divider.Text));
+                }
+            }
+            catch { CustomMessageBox.Show("Set VOLT_DIVIDER Failed"); }
+        }
+        private void TXT_divider_Validating(object sender, CancelEventArgs e)
+        {
+            float ans = 0;
+            e.Cancel = !float.TryParse(TXT_divider.Text, out ans);
+        }
+        private void TXT_divider_Validated(object sender, EventArgs e)
+        {
+            if (startup || ((TextBox)sender).Enabled == false)
+                return;
+            try
+            {
+                if (MainV2.comPort.param["VOLT_DIVIDER"] == null)
+                {
+                    CustomMessageBox.Show("Not Available");
+                }
+                else
+                {
+                    MainV2.comPort.setParam("VOLT_DIVIDER", float.Parse(TXT_divider.Text));
+                }
+            }
+            catch { CustomMessageBox.Show("Set VOLT_DIVIDER Failed"); }
+        }
+        private void TXT_ampspervolt_Validating(object sender, CancelEventArgs e)
+        {
+            float ans = 0;
+            e.Cancel = !float.TryParse(TXT_ampspervolt.Text, out ans);
+        }
+        private void TXT_ampspervolt_Validated(object sender, EventArgs e)
+        {
+            if (startup || ((TextBox)sender).Enabled == false)
+                return;
+            try
+            {
+                if (MainV2.comPort.param["AMP_PER_VOLT"] == null)
+                {
+                    CustomMessageBox.Show("Not Available");
+                }
+                else
+                {
+                    MainV2.comPort.setParam("AMP_PER_VOLT", float.Parse(TXT_ampspervolt.Text));
+                }
+            }
+            catch { CustomMessageBox.Show("Set AMP_PER_VOLT Failed"); }
+        }
+
+        private void CMB_batmonsensortype_SelectedIndexChanged(object sender, EventArgs e)
+        {
+            int selection = int.Parse(CMB_batmonsensortype.Text.Substring(0, 1));
+
+
+            if (selection == 1) // atto 45
+            {
+                float maxvolt = 13.6f;
+                float maxamps = 44.7f;
+                float mvpervolt = 242.3f;
+                float mvperamp = 73.20f;
+
+                // ~ 3.295v
+                float topvolt = (maxvolt * mvpervolt) / 1000;
+                // ~ 3.294v
+                float topamps = (maxamps * mvperamp) / 1000;
+
+                TXT_divider.Text = (maxvolt / topvolt).ToString();
+                TXT_ampspervolt.Text = (maxamps / topamps).ToString();
+            }
+            else if (selection == 2) // atto 90
+            {
+                float maxvolt = 50f;
+                float maxamps = 89.4f;
+                float mvpervolt = 63.69f;
+                float mvperamp = 36.60f;
+
+                float topvolt = (maxvolt * mvpervolt) / 1000;
+                float topamps = (maxamps * mvperamp) / 1000;
+
+                TXT_divider.Text = (maxvolt / topvolt).ToString();
+                TXT_ampspervolt.Text = (maxamps / topamps).ToString();
+            }
+            else if (selection == 3) // atto 180
+            {
+                float maxvolt = 50f;
+                float maxamps = 178.8f;
+                float mvpervolt = 63.69f;
+                float mvperamp = 18.30f;
+
+                float topvolt = (maxvolt * mvpervolt) / 1000;
+                float topamps = (maxamps * mvperamp) / 1000;
+
+                TXT_divider.Text = (maxvolt / topvolt).ToString();
+                TXT_ampspervolt.Text = (maxamps / topamps).ToString();
+            }
+
+            // enable to update
+            TXT_divider.Enabled = true;
+            TXT_ampspervolt.Enabled = true;
+            TXT_measuredvoltage.Enabled = true;
+            TXT_inputvoltage.Enabled = true;
+
+            // update
+            TXT_ampspervolt_Validated(TXT_ampspervolt, null);
+
+            TXT_divider_Validated(TXT_divider, null);
+
+            // disable
+            TXT_divider.Enabled = false;
+            TXT_ampspervolt.Enabled = false;
+            TXT_measuredvoltage.Enabled = false;
+
+            //reenable if needed
+            if (selection == 0)
+            {
+                TXT_divider.Enabled = true;
+                TXT_ampspervolt.Enabled = true;
+                TXT_measuredvoltage.Enabled = true;
+                TXT_inputvoltage.Enabled = true;
+            }
+        }
+
+        private void ConfigBatteryMonitoring_Load(object sender, EventArgs e)
+        {
+            if (!MainV2.comPort.BaseStream.IsOpen)
+            {
+                this.Enabled = false;
+                return;
+            }
+            else
+            {
+                this.Enabled = true;
+            }
+
+            startup = true;
+            bool not_supported = false;
+            if (MainV2.comPort.param["BATT_MONITOR"] != null)
+            {
+                if (MainV2.comPort.param["BATT_MONITOR"].ToString() != "0.0")
+                {
+                    CMB_batmontype.SelectedIndex = getIndex(CMB_batmontype, (int)float.Parse(MainV2.comPort.param["BATT_MONITOR"].ToString()));
+                }
+
+                // ignore language re . vs ,
+
+                if (TXT_ampspervolt.Text == (13.6612).ToString())
+                {
+                    CMB_batmonsensortype.SelectedIndex = 1;
+                }
+                else if (TXT_ampspervolt.Text == (27.3224).ToString())
+                {
+                    CMB_batmonsensortype.SelectedIndex = 2;
+                }
+                else if (TXT_ampspervolt.Text == (54.64481).ToString())
+                {
+                    CMB_batmonsensortype.SelectedIndex = 3;
+                }
+                else
+                {
+                    CMB_batmonsensortype.SelectedIndex = 0;
+                }
+
+            }
+
+            if (MainV2.comPort.param["BATT_CAPACITY"] != null)
+                TXT_battcapacity.Text = MainV2.comPort.param["BATT_CAPACITY"].ToString();
+            if (MainV2.comPort.param["INPUT_VOLTS"] != null)
+                TXT_inputvoltage.Text = MainV2.comPort.param["INPUT_VOLTS"].ToString();
+            else
+                not_supported = true;
+            TXT_voltage.Text = MainV2.cs.battery_voltage.ToString();
+            TXT_measuredvoltage.Text = TXT_voltage.Text;
+            if (MainV2.comPort.param["VOLT_DIVIDER"] != null)
+                TXT_divider.Text = MainV2.comPort.param["VOLT_DIVIDER"].ToString();
+            else
+                not_supported = true;
+            if (MainV2.comPort.param["AMP_PER_VOLT"] != null)
+                TXT_ampspervolt.Text = MainV2.comPort.param["AMP_PER_VOLT"].ToString();
+            else
+                not_supported = true;
+            if (not_supported)
+            {
+                TXT_inputvoltage.Enabled = false;
+                TXT_measuredvoltage.Enabled = false;
+                TXT_divider.Enabled = false;
+                TXT_ampspervolt.Enabled = false;
+            }
+
+            startup = false;
+        }
+
+        int getIndex(ComboBox ctl, int no)
+        {
+            foreach (var item in ctl.Items)
+            {
+                int ans = int.Parse(item.ToString().Substring(0, 1));
+
+                if (ans == no)
+                    return ctl.Items.IndexOf(item);
+            }
+
+            return -1;
+        }  
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.es-ES.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.es-ES.resx
new file mode 100644
index 0000000000000000000000000000000000000000..70ad73f1af84a8cec236442b9c51462353fceab5
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.es-ES.resx
@@ -0,0 +1,315 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manual</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Modo actual:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Habilitar el flujo óptico</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>NOTA: Las imágenes son sólo para su presentación</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Actual:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APMSetup</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Swash-Servo posición</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Activar Compas</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Ajuste Chásis (+ or x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modos</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Reset</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Superior</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Swash de Viaje</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manual</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Timón de Viaje</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibración del sensor de voltaje:Para calibrar el sensor, use un multímetro para medir la tensión que sale de la CES de la batería-la eliminación del circuito (se trata de cables negro y rojo en el cable de tres hilos que suministra energía a la placa APM).Luego reste 0,3 V de ese valor y entrar en él en el campo # 1 a la izquierda.</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrar Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Modo de Vuelo 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Alabeo Max</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Modo de Vuelo 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Cabeceo Max</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>por ejemplo, en grados 2 ° 3 'W es -2,3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Modo de Vuelo 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Nivel tu quad para establecer las compensaciones por defecto acel</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Modo de Vuelo 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacidad</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Declinación</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Activar Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Entrada Radio</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibración</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Modo de Vuelo 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Modo de Vuelo 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Gyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Sitio Web Declinación</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batería</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Cero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Activar Airspeed</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Restablecer los Ajustes de hardware APM</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.fr.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.fr.resx
new file mode 100644
index 0000000000000000000000000000000000000000..1bd274beea2e052315a0ab1e83d3619dcf47cbf1
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.fr.resx
@@ -0,0 +1,312 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manuel</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Mode Courant:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Activ. capteur optique</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>NOTE: images pou presentation uniquement. Fonctionnel pour Hex, Octo etc...</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Actuel:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APMSetup</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Swash-Servo position</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Activ. Boussole</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>type de châssis (+ ou x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modes</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Réinit.</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Haut</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Mouvement Swash</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manuel</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Deplac. du Gouvernail</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibration du capteur de Voltage.1. Mesurer le voltage sur APM et inscrivez-le dans la boite ci-bas.2. Mesurer le voltage de la batterie et inscrivez-le dans la boite ci-bas.3. Inscrire les ampères par volt de la documentation du capteur de courant ci-bas</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrer Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Mode de vol 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Roulis Max</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Mode de vol 2</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Tangage Max</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>en degrés eg 2° 3' W est -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Mode de vol 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Niveler l'apareil pour copensation des accels</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Mode de vol 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacité</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Déclination</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Activer Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Entrée Radio</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Mode de vol 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Mode de vol 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Gyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Matériel</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Site Web Déclination</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batterie</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zéro</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Activ. Airspeed</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>RàZ tout parametres du APM</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Moniteur</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.it-IT.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.it-IT.resx
new file mode 100644
index 0000000000000000000000000000000000000000..2b2636c8132c76e5855c9dbb2c87151786f287c3
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.it-IT.resx
@@ -0,0 +1,318 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manuale</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Modo Corrente:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Abilita Flusso ottico</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>Nota: le immagini sono sono per presentazione, funzionerà con Hexa, etc.</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevatore CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Corrente:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>Imposta APM</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Posizione del servo del piatto</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Abilita Magnetometro</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Imposta Frame (+ or x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modi</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Riavvia</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Alto</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Escursione del piatto</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manuale</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Escursione Timone</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibarzione del sensore di voltaggio:
+1. Misura il valtaggio di ingresso di APM e inseriscilo nel box sotto 
+2. Misura il voltaggio della batteria e inseriscilo nel box sotto 
+3. Dalle caratteristiche del sensore di corrente, inserisci il valore degli ampere per volt nel box qui sotto</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrazione Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Massimo</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Modo di volo 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Rollio massimo</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Modo di volo 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Passo massimo</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>in gradi es 2° 3' W is -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Modo di volo 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Livella il quad per impostare gli accelerometri</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Modo di volo 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacità</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Declinazione</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Attiva Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Ingresso Radio</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibration</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Modo di volo 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Modo di volo 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Giroscopio</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Sito Web per la Declinazione</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batteria</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Attiva Sensore Velocità</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Resetta APM ai valori di Default</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.pl.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.pl.resx
new file mode 100644
index 0000000000000000000000000000000000000000..057b9327168c6471be22139b5d017e20582de843
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.pl.resx
@@ -0,0 +1,318 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Ręczne</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Aktualny tryb:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Włącz Optical Flow</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>UWAGA: Obrazy są wyłącznie do prezentacji, działają jedynie z hexa, itp.</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Odwr. Elevon CH1</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>Aktualny PWM:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>Ustawienia APM</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Pozycja serwa płyty ster.</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Włącz kompas</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Ustawienie ramy (+ lub x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Tryby</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Reset</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Góra</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Zakres ruchu płyty sterującej</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Ręczne</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Zakres steru kierunku</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Kalibracja czujnika napięcia:
+1. Zmierz napięcie wejściowe APM i wpisz poniżej
+2. Zmierz napięcie baterii i wpisz poniżej
+3. Wpisz poniżej ilość amperów/wolt [A/V] z dokumentacji czujnika prądu</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Kalibracja radia</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Tryb lotu 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Max przechylenie</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Tryb lotu 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Max pochylenie</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>w stopniech np. 2° 3' W to -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Tryb lotu 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Wypoziomuj quada żeby stawić domyśle offsety przysp.</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Tryb lotu 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Pojemność</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Deklinacja</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Włącz sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Wejścia radia</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibration</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Tryb lotu 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Tryb lotu 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Żyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Strona www deklinacji</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Bateria</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Włącz prędkość powietrza</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Reset APM do stawień domyślnych</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx
new file mode 100644
index 0000000000000000000000000000000000000000..30ba0ba68e14bdb671d5442d84fbdc5ed1a34d4b
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.resx
@@ -0,0 +1,678 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
+  <data name="label31.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
+  <data name="label31.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="label31.Location" type="System.Drawing.Point, System.Drawing">
+    <value>5, 16</value>
+  </data>
+  <data name="label31.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 0, 2, 0</value>
+  </data>
+  <data name="label31.Size" type="System.Drawing.Size, System.Drawing">
+    <value>110, 13</value>
+  </data>
+  <data name="label31.TabIndex" type="System.Int32, mscorlib">
+    <value>29</value>
+  </data>
+  <data name="label31.Text" xml:space="preserve">
+    <value>1. APM Input voltage:</value>
+  </data>
+  <data name="&gt;&gt;label31.Name" xml:space="preserve">
+    <value>label31</value>
+  </data>
+  <data name="&gt;&gt;label31.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label31.Parent" xml:space="preserve">
+    <value>groupBox4</value>
+  </data>
+  <data name="&gt;&gt;label31.ZOrder" xml:space="preserve">
+    <value>0</value>
+  </data>
+  <data name="label32.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label32.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label32.Location" type="System.Drawing.Point, System.Drawing">
+    <value>5, 38</value>
+  </data>
+  <data name="label32.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 0, 2, 0</value>
+  </data>
+  <data name="label32.Size" type="System.Drawing.Size, System.Drawing">
+    <value>142, 13</value>
+  </data>
+  <data name="label32.TabIndex" type="System.Int32, mscorlib">
+    <value>30</value>
+  </data>
+  <data name="label32.Text" xml:space="preserve">
+    <value>2. Measured battery voltage:</value>
+  </data>
+  <data name="&gt;&gt;label32.Name" xml:space="preserve">
+    <value>label32</value>
+  </data>
+  <data name="&gt;&gt;label32.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label32.Parent" xml:space="preserve">
+    <value>groupBox4</value>
+  </data>
+  <data name="&gt;&gt;label32.ZOrder" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="label33.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label33.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label33.Location" type="System.Drawing.Point, System.Drawing">
+    <value>5, 60</value>
+  </data>
+  <data name="label33.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 0, 2, 0</value>
+  </data>
+  <data name="label33.Size" type="System.Drawing.Size, System.Drawing">
+    <value>135, 13</value>
+  </data>
+  <data name="label33.TabIndex" type="System.Int32, mscorlib">
+    <value>31</value>
+  </data>
+  <data name="label33.Text" xml:space="preserve">
+    <value>3. Battery voltage (Calced):</value>
+  </data>
+  <data name="&gt;&gt;label33.Name" xml:space="preserve">
+    <value>label33</value>
+  </data>
+  <data name="&gt;&gt;label33.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label33.Parent" xml:space="preserve">
+    <value>groupBox4</value>
+  </data>
+  <data name="&gt;&gt;label33.ZOrder" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="TXT_ampspervolt.Location" type="System.Drawing.Point, System.Drawing">
+    <value>149, 100</value>
+  </data>
+  <data name="TXT_ampspervolt.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 2, 2, 2</value>
+  </data>
+  <data name="TXT_ampspervolt.Size" type="System.Drawing.Size, System.Drawing">
+    <value>76, 20</value>
+  </data>
+  <data name="TXT_ampspervolt.TabIndex" type="System.Int32, mscorlib">
+    <value>38</value>
+  </data>
+  <data name="&gt;&gt;TXT_ampspervolt.Name" xml:space="preserve">
+    <value>TXT_ampspervolt</value>
+  </data>
+  <data name="&gt;&gt;TXT_ampspervolt.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;TXT_ampspervolt.Parent" xml:space="preserve">
+    <value>groupBox4</value>
+  </data>
+  <data name="&gt;&gt;TXT_ampspervolt.ZOrder" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="label34.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label34.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label34.Location" type="System.Drawing.Point, System.Drawing">
+    <value>5, 81</value>
+  </data>
+  <data name="label34.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 0, 2, 0</value>
+  </data>
+  <data name="label34.Size" type="System.Drawing.Size, System.Drawing">
+    <value>134, 13</value>
+  </data>
+  <data name="label34.TabIndex" type="System.Int32, mscorlib">
+    <value>32</value>
+  </data>
+  <data name="label34.Text" xml:space="preserve">
+    <value>4. Voltage divider (Calced):</value>
+  </data>
+  <data name="&gt;&gt;label34.Name" xml:space="preserve">
+    <value>label34</value>
+  </data>
+  <data name="&gt;&gt;label34.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label34.Parent" xml:space="preserve">
+    <value>groupBox4</value>
+  </data>
+  <data name="&gt;&gt;label34.ZOrder" xml:space="preserve">
+    <value>4</value>
+  </data>
+  <data name="TXT_divider.Location" type="System.Drawing.Point, System.Drawing">
+    <value>149, 78</value>
+  </data>
+  <data name="TXT_divider.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 2, 2, 2</value>
+  </data>
+  <data name="TXT_divider.Size" type="System.Drawing.Size, System.Drawing">
+    <value>76, 20</value>
+  </data>
+  <data name="TXT_divider.TabIndex" type="System.Int32, mscorlib">
+    <value>37</value>
+  </data>
+  <data name="&gt;&gt;TXT_divider.Name" xml:space="preserve">
+    <value>TXT_divider</value>
+  </data>
+  <data name="&gt;&gt;TXT_divider.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;TXT_divider.Parent" xml:space="preserve">
+    <value>groupBox4</value>
+  </data>
+  <data name="&gt;&gt;TXT_divider.ZOrder" xml:space="preserve">
+    <value>5</value>
+  </data>
+  <data name="label35.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label35.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label35.Location" type="System.Drawing.Point, System.Drawing">
+    <value>6, 103</value>
+  </data>
+  <data name="label35.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 0, 2, 0</value>
+  </data>
+  <data name="label35.Size" type="System.Drawing.Size, System.Drawing">
+    <value>101, 13</value>
+  </data>
+  <data name="label35.TabIndex" type="System.Int32, mscorlib">
+    <value>33</value>
+  </data>
+  <data name="label35.Text" xml:space="preserve">
+    <value>5. Amperes per volt:</value>
+  </data>
+  <data name="&gt;&gt;label35.Name" xml:space="preserve">
+    <value>label35</value>
+  </data>
+  <data name="&gt;&gt;label35.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label35.Parent" xml:space="preserve">
+    <value>groupBox4</value>
+  </data>
+  <data name="&gt;&gt;label35.ZOrder" xml:space="preserve">
+    <value>6</value>
+  </data>
+  <data name="TXT_voltage.Location" type="System.Drawing.Point, System.Drawing">
+    <value>149, 57</value>
+  </data>
+  <data name="TXT_voltage.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 2, 2, 2</value>
+  </data>
+  <data name="TXT_voltage.Size" type="System.Drawing.Size, System.Drawing">
+    <value>76, 20</value>
+  </data>
+  <data name="TXT_voltage.TabIndex" type="System.Int32, mscorlib">
+    <value>36</value>
+  </data>
+  <data name="&gt;&gt;TXT_voltage.Name" xml:space="preserve">
+    <value>TXT_voltage</value>
+  </data>
+  <data name="&gt;&gt;TXT_voltage.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;TXT_voltage.Parent" xml:space="preserve">
+    <value>groupBox4</value>
+  </data>
+  <data name="&gt;&gt;TXT_voltage.ZOrder" xml:space="preserve">
+    <value>7</value>
+  </data>
+  <data name="TXT_inputvoltage.Location" type="System.Drawing.Point, System.Drawing">
+    <value>149, 13</value>
+  </data>
+  <data name="TXT_inputvoltage.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 2, 2, 2</value>
+  </data>
+  <data name="TXT_inputvoltage.Size" type="System.Drawing.Size, System.Drawing">
+    <value>76, 20</value>
+  </data>
+  <data name="TXT_inputvoltage.TabIndex" type="System.Int32, mscorlib">
+    <value>34</value>
+  </data>
+  <data name="&gt;&gt;TXT_inputvoltage.Name" xml:space="preserve">
+    <value>TXT_inputvoltage</value>
+  </data>
+  <data name="&gt;&gt;TXT_inputvoltage.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;TXT_inputvoltage.Parent" xml:space="preserve">
+    <value>groupBox4</value>
+  </data>
+  <data name="&gt;&gt;TXT_inputvoltage.ZOrder" xml:space="preserve">
+    <value>8</value>
+  </data>
+  <data name="TXT_measuredvoltage.Location" type="System.Drawing.Point, System.Drawing">
+    <value>149, 35</value>
+  </data>
+  <data name="TXT_measuredvoltage.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 2, 2, 2</value>
+  </data>
+  <data name="TXT_measuredvoltage.Size" type="System.Drawing.Size, System.Drawing">
+    <value>76, 20</value>
+  </data>
+  <data name="TXT_measuredvoltage.TabIndex" type="System.Int32, mscorlib">
+    <value>35</value>
+  </data>
+  <data name="&gt;&gt;TXT_measuredvoltage.Name" xml:space="preserve">
+    <value>TXT_measuredvoltage</value>
+  </data>
+  <data name="&gt;&gt;TXT_measuredvoltage.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;TXT_measuredvoltage.Parent" xml:space="preserve">
+    <value>groupBox4</value>
+  </data>
+  <data name="&gt;&gt;TXT_measuredvoltage.ZOrder" xml:space="preserve">
+    <value>9</value>
+  </data>
+  <data name="groupBox4.Location" type="System.Drawing.Point, System.Drawing">
+    <value>14, 172</value>
+  </data>
+  <data name="groupBox4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>238, 131</value>
+  </data>
+  <data name="groupBox4.TabIndex" type="System.Int32, mscorlib">
+    <value>50</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibration</value>
+  </data>
+  <data name="&gt;&gt;groupBox4.Name" xml:space="preserve">
+    <value>groupBox4</value>
+  </data>
+  <data name="&gt;&gt;groupBox4.Type" xml:space="preserve">
+    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;groupBox4.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;groupBox4.ZOrder" xml:space="preserve">
+    <value>0</value>
+  </data>
+  <data name="label47.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label47.Location" type="System.Drawing.Point, System.Drawing">
+    <value>106, 71</value>
+  </data>
+  <data name="label47.Size" type="System.Drawing.Size, System.Drawing">
+    <value>42, 13</value>
+  </data>
+  <data name="label47.TabIndex" type="System.Int32, mscorlib">
+    <value>49</value>
+  </data>
+  <data name="label47.Text" xml:space="preserve">
+    <value>Sensor</value>
+  </data>
+  <data name="&gt;&gt;label47.Name" xml:space="preserve">
+    <value>label47</value>
+  </data>
+  <data name="&gt;&gt;label47.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label47.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label47.ZOrder" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CMB_batmonsensortype.Items" xml:space="preserve">
+    <value>0: Other</value>
+  </data>
+  <data name="CMB_batmonsensortype.Items1" xml:space="preserve">
+    <value>1: AttoPilot 45A</value>
+  </data>
+  <data name="CMB_batmonsensortype.Items2" xml:space="preserve">
+    <value>2: AttoPilot 90A</value>
+  </data>
+  <data name="CMB_batmonsensortype.Items3" xml:space="preserve">
+    <value>3: AttoPilot 180A</value>
+  </data>
+  <data name="CMB_batmonsensortype.Location" type="System.Drawing.Point, System.Drawing">
+    <value>160, 68</value>
+  </data>
+  <data name="CMB_batmonsensortype.Size" type="System.Drawing.Size, System.Drawing">
+    <value>121, 21</value>
+  </data>
+  <data name="CMB_batmonsensortype.TabIndex" type="System.Int32, mscorlib">
+    <value>48</value>
+  </data>
+  <data name="&gt;&gt;CMB_batmonsensortype.Name" xml:space="preserve">
+    <value>CMB_batmonsensortype</value>
+  </data>
+  <data name="&gt;&gt;CMB_batmonsensortype.Type" xml:space="preserve">
+    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CMB_batmonsensortype.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CMB_batmonsensortype.ZOrder" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="textBox3.Font" type="System.Drawing.Font, System.Drawing">
+    <value>Microsoft Sans Serif, 8.25pt</value>
+  </data>
+  <data name="textBox3.Location" type="System.Drawing.Point, System.Drawing">
+    <value>282, 172</value>
+  </data>
+  <data name="textBox3.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 2, 2, 2</value>
+  </data>
+  <data name="textBox3.Multiline" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="textBox3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>219, 131</value>
+  </data>
+  <data name="textBox3.TabIndex" type="System.Int32, mscorlib">
+    <value>47</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Voltage sensor calibration:
+To calibrate your sensor, use a multimeter to measure the voltage coming out of your ESC's battery-elimination circuit (these are black and red wires in the three-wire cable that is powering your APM board).
+Then subtract 0.3v from that value and enter it in field #1 at left.
+</value>
+  </data>
+  <data name="&gt;&gt;textBox3.Name" xml:space="preserve">
+    <value>textBox3</value>
+  </data>
+  <data name="&gt;&gt;textBox3.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;textBox3.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;textBox3.ZOrder" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="label29.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label29.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label29.Location" type="System.Drawing.Point, System.Drawing">
+    <value>288, 45</value>
+  </data>
+  <data name="label29.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 13</value>
+  </data>
+  <data name="label29.TabIndex" type="System.Int32, mscorlib">
+    <value>43</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacity</value>
+  </data>
+  <data name="&gt;&gt;label29.Name" xml:space="preserve">
+    <value>label29</value>
+  </data>
+  <data name="&gt;&gt;label29.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label29.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label29.ZOrder" xml:space="preserve">
+    <value>4</value>
+  </data>
+  <data name="label30.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label30.Location" type="System.Drawing.Point, System.Drawing">
+    <value>106, 45</value>
+  </data>
+  <data name="label30.Size" type="System.Drawing.Size, System.Drawing">
+    <value>42, 13</value>
+  </data>
+  <data name="label30.TabIndex" type="System.Int32, mscorlib">
+    <value>44</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+  <data name="&gt;&gt;label30.Name" xml:space="preserve">
+    <value>label30</value>
+  </data>
+  <data name="&gt;&gt;label30.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label30.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label30.ZOrder" xml:space="preserve">
+    <value>5</value>
+  </data>
+  <data name="TXT_battcapacity.Location" type="System.Drawing.Point, System.Drawing">
+    <value>349, 42</value>
+  </data>
+  <data name="TXT_battcapacity.Size" type="System.Drawing.Size, System.Drawing">
+    <value>83, 20</value>
+  </data>
+  <data name="TXT_battcapacity.TabIndex" type="System.Int32, mscorlib">
+    <value>45</value>
+  </data>
+  <data name="&gt;&gt;TXT_battcapacity.Name" xml:space="preserve">
+    <value>TXT_battcapacity</value>
+  </data>
+  <data name="&gt;&gt;TXT_battcapacity.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;TXT_battcapacity.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;TXT_battcapacity.ZOrder" xml:space="preserve">
+    <value>6</value>
+  </data>
+  <data name="CMB_batmontype.Items" xml:space="preserve">
+    <value>0: Disabled</value>
+  </data>
+  <data name="CMB_batmontype.Items1" xml:space="preserve">
+    <value>3: Battery Volts</value>
+  </data>
+  <data name="CMB_batmontype.Items2" xml:space="preserve">
+    <value>4: Volts &amp; Current</value>
+  </data>
+  <data name="CMB_batmontype.Location" type="System.Drawing.Point, System.Drawing">
+    <value>160, 41</value>
+  </data>
+  <data name="CMB_batmontype.Size" type="System.Drawing.Size, System.Drawing">
+    <value>121, 21</value>
+  </data>
+  <data name="CMB_batmontype.TabIndex" type="System.Int32, mscorlib">
+    <value>46</value>
+  </data>
+  <data name="&gt;&gt;CMB_batmontype.Name" xml:space="preserve">
+    <value>CMB_batmontype</value>
+  </data>
+  <data name="&gt;&gt;CMB_batmontype.Type" xml:space="preserve">
+    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CMB_batmontype.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CMB_batmontype.ZOrder" xml:space="preserve">
+    <value>7</value>
+  </data>
+  <data name="pictureBox5.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
+    <value>Zoom</value>
+  </data>
+  <data name="pictureBox5.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="pictureBox5.Location" type="System.Drawing.Point, System.Drawing">
+    <value>14, 16</value>
+  </data>
+  <data name="pictureBox5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>75, 75</value>
+  </data>
+  <data name="pictureBox5.TabIndex" type="System.Int32, mscorlib">
+    <value>42</value>
+  </data>
+  <data name="&gt;&gt;pictureBox5.Name" xml:space="preserve">
+    <value>pictureBox5</value>
+  </data>
+  <data name="&gt;&gt;pictureBox5.Type" xml:space="preserve">
+    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;pictureBox5.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;pictureBox5.ZOrder" xml:space="preserve">
+    <value>8</value>
+  </data>
+  <metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
+    <value>True</value>
+  </metadata>
+  <data name="$this.AutoScaleDimensions" type="System.Drawing.SizeF, System.Drawing">
+    <value>6, 13</value>
+  </data>
+  <data name="$this.Size" type="System.Drawing.Size, System.Drawing">
+    <value>518, 322</value>
+  </data>
+  <data name="&gt;&gt;$this.Name" xml:space="preserve">
+    <value>ConfigBatteryMonitoring</value>
+  </data>
+  <data name="&gt;&gt;$this.Type" xml:space="preserve">
+    <value>System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.zh-Hans.resx
new file mode 100644
index 0000000000000000000000000000000000000000..f96892c423b112b28127ad582686f33464b57c5b
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.zh-Hans.resx
@@ -0,0 +1,496 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>遥控输入</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>模式</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>硬件</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>电池</value>
+  </data>
+  <data name="tabHeli.Text" xml:space="preserve">
+    <value>AC2 直升机</value>
+  </data>
+  <data name="groupBoxElevons.Text" xml:space="preserve">
+    <value>上降副翼 (Elevon) 配置</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="CHK_elevonch2rev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>115, 17</value>
+  </data>
+  <data name="CHK_elevonch2rev.Text" xml:space="preserve">
+    <value>Elevons CH2 逆转</value>
+  </data>
+  <data name="CHK_elevonrev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>91, 17</value>
+  </data>
+  <data name="CHK_elevonrev.Text" xml:space="preserve">
+    <value>Elevons 逆转</value>
+  </data>
+  <data name="CHK_elevonch1rev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>115, 17</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 逆转</value>
+  </data>
+  <data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch3.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch4.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch2.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch1.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>校准遥控</value>
+  </data>
+  <data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="label14.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>当前 PWM:</value>
+  </data>
+  <data name="label13.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>当前模式:</value>
+  </data>
+  <data name="label6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>飞行模式 6</value>
+  </data>
+  <data name="label5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>飞行模式 5</value>
+  </data>
+  <data name="label4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>飞行模式 4</value>
+  </data>
+  <data name="label3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>飞行模式 3</value>
+  </data>
+  <data name="label2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>飞行模式 2</value>
+  </data>
+  <data name="label1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>飞行模式 1</value>
+  </data>
+  <data name="BUT_SaveModes.Text" xml:space="preserve">
+    <value>保存模式</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>十进制, 2° 3' W 就是 -2.3</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>启用光流</value>
+  </data>
+  <data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
+    <value>67, 13</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>磁偏角网站</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>磁偏角</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>启用空速计</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>启用声纳</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>启用罗盘</value>
+  </data>
+  <data name="label31.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label31.Text" xml:space="preserve">
+    <value>输入电压:</value>
+  </data>
+  <data name="label32.Size" type="System.Drawing.Size, System.Drawing">
+    <value>94, 13</value>
+  </data>
+  <data name="label32.Text" xml:space="preserve">
+    <value>测量的电池电压:</value>
+  </data>
+  <data name="label33.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label33.Text" xml:space="preserve">
+    <value>电池电压:</value>
+  </data>
+  <data name="label34.Size" type="System.Drawing.Size, System.Drawing">
+    <value>52, 13</value>
+  </data>
+  <data name="label34.Text" xml:space="preserve">
+    <value>分 压 比:</value>
+  </data>
+  <data name="label35.Size" type="System.Drawing.Size, System.Drawing">
+    <value>63, 13</value>
+  </data>
+  <data name="label35.Text" xml:space="preserve">
+    <value>安培/伏特:</value>
+  </data>
+  <data name="label47.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 18</value>
+  </data>
+  <data name="label47.Text" xml:space="preserve">
+    <value>传感器</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>电压传感器校准:
+1. 测量APM输入电压,输入到下方的文本框中
+2. 测量电池电压,输入到下方的文本框中
+3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中</value>
+  </data>
+  <data name="label29.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>容量</value>
+  </data>
+  <data name="label30.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 13</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>监控器</value>
+  </data>
+  <data name="label28.Size" type="System.Drawing.Size, System.Drawing">
+    <value>175, 13</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>设置水平面的默认加速度计偏移</value>
+  </data>
+  <data name="label16.Size" type="System.Drawing.Size, System.Drawing">
+    <value>261, 13</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>注: 图片只是用于展示,设置可以用于六轴等机架</value>
+  </data>
+  <data name="label15.Size" type="System.Drawing.Size, System.Drawing">
+    <value>93, 13</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>机架设置 (+ 或 x)</value>
+  </data>
+  <data name="BUT_levelac2.Text" xml:space="preserve">
+    <value>找平</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>手动</value>
+  </data>
+  <data name="BUT_swash_manual.Text" xml:space="preserve">
+    <value>手动</value>
+  </data>
+  <data name="label46.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label46.Text" xml:space="preserve">
+    <value>感度</value>
+  </data>
+  <data name="label45.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label45.Text" xml:space="preserve">
+    <value>启用</value>
+  </data>
+  <data name="label44.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label44.Text" xml:space="preserve">
+    <value>微调</value>
+  </data>
+  <data name="label43.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label43.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="label42.Size" type="System.Drawing.Size, System.Drawing">
+    <value>43, 13</value>
+  </data>
+  <data name="label42.Text" xml:space="preserve">
+    <value>方向舵</value>
+  </data>
+  <data name="label24.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>最大</value>
+  </data>
+  <data name="label40.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label40.Text" xml:space="preserve">
+    <value>最小</value>
+  </data>
+  <data name="label41.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label41.Text" xml:space="preserve">
+    <value>最低</value>
+  </data>
+  <data name="label21.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>最高</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>0度</value>
+  </data>
+  <data name="label39.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label39.Text" xml:space="preserve">
+    <value>微调</value>
+  </data>
+  <data name="label38.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label38.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="label37.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label37.Text" xml:space="preserve">
+    <value>位置</value>
+  </data>
+  <data name="label36.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label36.Text" xml:space="preserve">
+    <value>舵机</value>
+  </data>
+  <data name="label26.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>最大俯仰</value>
+  </data>
+  <data name="label25.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>最大侧倾</value>
+  </data>
+  <data name="label23.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>舵机行程</value>
+  </data>
+  <data name="label22.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>斜盘水平微调</value>
+  </data>
+  <data name="label17.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>斜盘舵机位置</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>重置</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>重置 APM 为默认设置</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APM设置</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.zh-TW.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.zh-TW.resx
new file mode 100644
index 0000000000000000000000000000000000000000..0c03fbf8ed6bd5befc34246175bf1adf106cce43
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.zh-TW.resx
@@ -0,0 +1,460 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>重置</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>遙控輸入</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>模式</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>硬件</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>電池</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>重置 APM 為默認設置</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch3.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch4.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch2.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch1.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>校準遙控</value>
+  </data>
+  <data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="label14.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>當前 PWM:</value>
+  </data>
+  <data name="label13.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>當前模式:</value>
+  </data>
+  <data name="label6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>飛行模式 6</value>
+  </data>
+  <data name="label5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>飛行模式 5</value>
+  </data>
+  <data name="label4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>飛行模式 4</value>
+  </data>
+  <data name="label3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>飛行模式 3</value>
+  </data>
+  <data name="label2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>飛行模式 2</value>
+  </data>
+  <data name="label1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>飛行模式 1</value>
+  </data>
+  <data name="BUT_SaveModes.Text" xml:space="preserve">
+    <value>保存模式</value>
+  </data>
+  <data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
+    <value>67, 13</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>磁偏角網站</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>磁偏角</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>啟用空速計</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>啟用聲納</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>啟用羅盤</value>
+  </data>
+  <data name="label35.Size" type="System.Drawing.Size, System.Drawing">
+    <value>63, 13</value>
+  </data>
+  <data name="label35.Text" xml:space="preserve">
+    <value>安培/伏特:</value>
+  </data>
+  <data name="label34.Size" type="System.Drawing.Size, System.Drawing">
+    <value>52, 13</value>
+  </data>
+  <data name="label34.Text" xml:space="preserve">
+    <value>分 壓 比:</value>
+  </data>
+  <data name="label33.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label33.Text" xml:space="preserve">
+    <value>電池電壓:</value>
+  </data>
+  <data name="label32.Size" type="System.Drawing.Size, System.Drawing">
+    <value>94, 13</value>
+  </data>
+  <data name="label32.Text" xml:space="preserve">
+    <value>測量的電池電壓:</value>
+  </data>
+  <data name="label31.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label31.Text" xml:space="preserve">
+    <value>輸入電壓:</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>電壓傳感器校準:
+1. 測量APM輸入電壓,輸入到下方的文本框中
+2. 測量電池電壓,輸入到下方的文本框中
+3. 從當前的傳感器的數據表中找到安培/伏特,輸入到下方的文本框中</value>
+  </data>
+  <data name="label29.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>容量</value>
+  </data>
+  <data name="label30.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 13</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>監控器</value>
+  </data>
+  <data name="label28.Size" type="System.Drawing.Size, System.Drawing">
+    <value>175, 13</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>設置水平面的默認加速度計偏移</value>
+  </data>
+  <data name="label16.Size" type="System.Drawing.Size, System.Drawing">
+    <value>261, 13</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>注: 圖片只是用於展示,設置可以用於六軸等機架</value>
+  </data>
+  <data name="label15.Size" type="System.Drawing.Size, System.Drawing">
+    <value>93, 13</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>機架設置 (+ 或 x)</value>
+  </data>
+  <data name="BUT_levelac2.Text" xml:space="preserve">
+    <value>找平</value>
+  </data>
+  <data name="label46.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label46.Text" xml:space="preserve">
+    <value>感度</value>
+  </data>
+  <data name="label45.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label45.Text" xml:space="preserve">
+    <value>啟用</value>
+  </data>
+  <data name="label44.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label44.Text" xml:space="preserve">
+    <value>微調</value>
+  </data>
+  <data name="label43.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label43.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="label42.Size" type="System.Drawing.Size, System.Drawing">
+    <value>43, 13</value>
+  </data>
+  <data name="label42.Text" xml:space="preserve">
+    <value>方向舵</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>手動</value>
+  </data>
+  <data name="label24.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>最大</value>
+  </data>
+  <data name="label40.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label40.Text" xml:space="preserve">
+    <value>最小</value>
+  </data>
+  <data name="BUT_swash_manual.Text" xml:space="preserve">
+    <value>手動</value>
+  </data>
+  <data name="label41.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label41.Text" xml:space="preserve">
+    <value>最低</value>
+  </data>
+  <data name="label21.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>最高</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>0度</value>
+  </data>
+  <data name="label39.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label39.Text" xml:space="preserve">
+    <value>微調</value>
+  </data>
+  <data name="label38.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label38.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="label37.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label37.Text" xml:space="preserve">
+    <value>位置</value>
+  </data>
+  <data name="label36.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label36.Text" xml:space="preserve">
+    <value>舵機</value>
+  </data>
+  <data name="label26.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>最大俯仰</value>
+  </data>
+  <data name="label25.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>最大側傾</value>
+  </data>
+  <data name="label23.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>舵機行程</value>
+  </data>
+  <data name="label22.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>斜盤水平微調</value>
+  </data>
+  <data name="label17.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>斜盤舵機位置</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APM設置</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs
new file mode 100644
index 0000000000000000000000000000000000000000..6117c75a51e84b04c9b239124719bc0fe1598d55
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs
@@ -0,0 +1,318 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    partial class ConfigFlightModes
+    {
+        /// <summary> 
+        /// Required designer variable.
+        /// </summary>
+        private System.ComponentModel.IContainer components = null;
+
+        /// <summary> 
+        /// Clean up any resources being used.
+        /// </summary>
+        /// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
+        protected override void Dispose(bool disposing)
+        {
+            if (disposing && (components != null))
+            {
+                components.Dispose();
+            }
+            base.Dispose(disposing);
+        }
+
+        #region Component Designer generated code
+
+        /// <summary> 
+        /// Required method for Designer support - do not modify 
+        /// the contents of this method with the code editor.
+        /// </summary>
+        private void InitializeComponent()
+        {
+            this.components = new System.ComponentModel.Container();
+            System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigFlightModes));
+            this.CB_simple6 = new System.Windows.Forms.CheckBox();
+            this.CB_simple5 = new System.Windows.Forms.CheckBox();
+            this.CB_simple4 = new System.Windows.Forms.CheckBox();
+            this.CB_simple3 = new System.Windows.Forms.CheckBox();
+            this.CB_simple2 = new System.Windows.Forms.CheckBox();
+            this.CB_simple1 = new System.Windows.Forms.CheckBox();
+            this.label14 = new System.Windows.Forms.Label();
+            this.LBL_flightmodepwm = new System.Windows.Forms.Label();
+            this.label13 = new System.Windows.Forms.Label();
+            this.lbl_currentmode = new System.Windows.Forms.Label();
+            this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components);
+            this.label12 = new System.Windows.Forms.Label();
+            this.label11 = new System.Windows.Forms.Label();
+            this.label10 = new System.Windows.Forms.Label();
+            this.label9 = new System.Windows.Forms.Label();
+            this.label8 = new System.Windows.Forms.Label();
+            this.label7 = new System.Windows.Forms.Label();
+            this.label6 = new System.Windows.Forms.Label();
+            this.CMB_fmode6 = new System.Windows.Forms.ComboBox();
+            this.label5 = new System.Windows.Forms.Label();
+            this.CMB_fmode5 = new System.Windows.Forms.ComboBox();
+            this.label4 = new System.Windows.Forms.Label();
+            this.CMB_fmode4 = new System.Windows.Forms.ComboBox();
+            this.label3 = new System.Windows.Forms.Label();
+            this.CMB_fmode3 = new System.Windows.Forms.ComboBox();
+            this.label2 = new System.Windows.Forms.Label();
+            this.CMB_fmode2 = new System.Windows.Forms.ComboBox();
+            this.label1 = new System.Windows.Forms.Label();
+            this.CMB_fmode1 = new System.Windows.Forms.ComboBox();
+            this.BUT_SaveModes = new ArdupilotMega.MyButton();
+            ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit();
+            this.SuspendLayout();
+            // 
+            // CB_simple6
+            // 
+            resources.ApplyResources(this.CB_simple6, "CB_simple6");
+            this.CB_simple6.Name = "CB_simple6";
+            this.CB_simple6.UseVisualStyleBackColor = true;
+            // 
+            // CB_simple5
+            // 
+            resources.ApplyResources(this.CB_simple5, "CB_simple5");
+            this.CB_simple5.Name = "CB_simple5";
+            this.CB_simple5.UseVisualStyleBackColor = true;
+            // 
+            // CB_simple4
+            // 
+            resources.ApplyResources(this.CB_simple4, "CB_simple4");
+            this.CB_simple4.Name = "CB_simple4";
+            this.CB_simple4.UseVisualStyleBackColor = true;
+            // 
+            // CB_simple3
+            // 
+            resources.ApplyResources(this.CB_simple3, "CB_simple3");
+            this.CB_simple3.Name = "CB_simple3";
+            this.CB_simple3.UseVisualStyleBackColor = true;
+            // 
+            // CB_simple2
+            // 
+            resources.ApplyResources(this.CB_simple2, "CB_simple2");
+            this.CB_simple2.Name = "CB_simple2";
+            this.CB_simple2.UseVisualStyleBackColor = true;
+            // 
+            // CB_simple1
+            // 
+            resources.ApplyResources(this.CB_simple1, "CB_simple1");
+            this.CB_simple1.Name = "CB_simple1";
+            this.CB_simple1.UseVisualStyleBackColor = true;
+            // 
+            // label14
+            // 
+            resources.ApplyResources(this.label14, "label14");
+            this.label14.Name = "label14";
+            // 
+            // LBL_flightmodepwm
+            // 
+            resources.ApplyResources(this.LBL_flightmodepwm, "LBL_flightmodepwm");
+            this.LBL_flightmodepwm.Name = "LBL_flightmodepwm";
+            // 
+            // label13
+            // 
+            resources.ApplyResources(this.label13, "label13");
+            this.label13.Name = "label13";
+            // 
+            // lbl_currentmode
+            // 
+            resources.ApplyResources(this.lbl_currentmode, "lbl_currentmode");
+            this.lbl_currentmode.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.currentStateBindingSource, "mode", true));
+            this.lbl_currentmode.Name = "lbl_currentmode";
+            // 
+            // label12
+            // 
+            resources.ApplyResources(this.label12, "label12");
+            this.label12.Name = "label12";
+            // 
+            // label11
+            // 
+            resources.ApplyResources(this.label11, "label11");
+            this.label11.Name = "label11";
+            // 
+            // label10
+            // 
+            resources.ApplyResources(this.label10, "label10");
+            this.label10.Name = "label10";
+            // 
+            // label9
+            // 
+            resources.ApplyResources(this.label9, "label9");
+            this.label9.Name = "label9";
+            // 
+            // label8
+            // 
+            resources.ApplyResources(this.label8, "label8");
+            this.label8.Name = "label8";
+            // 
+            // label7
+            // 
+            resources.ApplyResources(this.label7, "label7");
+            this.label7.Name = "label7";
+            // 
+            // label6
+            // 
+            resources.ApplyResources(this.label6, "label6");
+            this.label6.Name = "label6";
+            // 
+            // CMB_fmode6
+            // 
+            this.CMB_fmode6.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend;
+            this.CMB_fmode6.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems;
+            this.CMB_fmode6.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CMB_fmode6.FormattingEnabled = true;
+            resources.ApplyResources(this.CMB_fmode6, "CMB_fmode6");
+            this.CMB_fmode6.Name = "CMB_fmode6";
+            // 
+            // label5
+            // 
+            resources.ApplyResources(this.label5, "label5");
+            this.label5.Name = "label5";
+            // 
+            // CMB_fmode5
+            // 
+            this.CMB_fmode5.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend;
+            this.CMB_fmode5.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems;
+            this.CMB_fmode5.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CMB_fmode5.FormattingEnabled = true;
+            resources.ApplyResources(this.CMB_fmode5, "CMB_fmode5");
+            this.CMB_fmode5.Name = "CMB_fmode5";
+            // 
+            // label4
+            // 
+            resources.ApplyResources(this.label4, "label4");
+            this.label4.Name = "label4";
+            // 
+            // CMB_fmode4
+            // 
+            this.CMB_fmode4.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend;
+            this.CMB_fmode4.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems;
+            this.CMB_fmode4.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CMB_fmode4.FormattingEnabled = true;
+            resources.ApplyResources(this.CMB_fmode4, "CMB_fmode4");
+            this.CMB_fmode4.Name = "CMB_fmode4";
+            // 
+            // label3
+            // 
+            resources.ApplyResources(this.label3, "label3");
+            this.label3.Name = "label3";
+            // 
+            // CMB_fmode3
+            // 
+            this.CMB_fmode3.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend;
+            this.CMB_fmode3.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems;
+            this.CMB_fmode3.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CMB_fmode3.FormattingEnabled = true;
+            resources.ApplyResources(this.CMB_fmode3, "CMB_fmode3");
+            this.CMB_fmode3.Name = "CMB_fmode3";
+            // 
+            // label2
+            // 
+            resources.ApplyResources(this.label2, "label2");
+            this.label2.Name = "label2";
+            // 
+            // CMB_fmode2
+            // 
+            this.CMB_fmode2.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend;
+            this.CMB_fmode2.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems;
+            this.CMB_fmode2.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CMB_fmode2.FormattingEnabled = true;
+            resources.ApplyResources(this.CMB_fmode2, "CMB_fmode2");
+            this.CMB_fmode2.Name = "CMB_fmode2";
+            // 
+            // label1
+            // 
+            resources.ApplyResources(this.label1, "label1");
+            this.label1.Name = "label1";
+            // 
+            // CMB_fmode1
+            // 
+            this.CMB_fmode1.AutoCompleteMode = System.Windows.Forms.AutoCompleteMode.SuggestAppend;
+            this.CMB_fmode1.AutoCompleteSource = System.Windows.Forms.AutoCompleteSource.ListItems;
+            this.CMB_fmode1.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CMB_fmode1.FormattingEnabled = true;
+            resources.ApplyResources(this.CMB_fmode1, "CMB_fmode1");
+            this.CMB_fmode1.Name = "CMB_fmode1";
+            // 
+            // BUT_SaveModes
+            // 
+            resources.ApplyResources(this.BUT_SaveModes, "BUT_SaveModes");
+            this.BUT_SaveModes.Name = "BUT_SaveModes";
+            this.BUT_SaveModes.UseVisualStyleBackColor = true;
+            this.BUT_SaveModes.Click += new System.EventHandler(this.BUT_SaveModes_Click);
+            // 
+            // ConfigFlightModes
+            // 
+            resources.ApplyResources(this, "$this");
+            this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+            this.Controls.Add(this.CB_simple6);
+            this.Controls.Add(this.CB_simple5);
+            this.Controls.Add(this.CB_simple4);
+            this.Controls.Add(this.CB_simple3);
+            this.Controls.Add(this.CB_simple2);
+            this.Controls.Add(this.CB_simple1);
+            this.Controls.Add(this.label14);
+            this.Controls.Add(this.LBL_flightmodepwm);
+            this.Controls.Add(this.label13);
+            this.Controls.Add(this.lbl_currentmode);
+            this.Controls.Add(this.label12);
+            this.Controls.Add(this.label11);
+            this.Controls.Add(this.label10);
+            this.Controls.Add(this.label9);
+            this.Controls.Add(this.label8);
+            this.Controls.Add(this.label7);
+            this.Controls.Add(this.label6);
+            this.Controls.Add(this.CMB_fmode6);
+            this.Controls.Add(this.label5);
+            this.Controls.Add(this.CMB_fmode5);
+            this.Controls.Add(this.label4);
+            this.Controls.Add(this.CMB_fmode4);
+            this.Controls.Add(this.label3);
+            this.Controls.Add(this.CMB_fmode3);
+            this.Controls.Add(this.label2);
+            this.Controls.Add(this.CMB_fmode2);
+            this.Controls.Add(this.label1);
+            this.Controls.Add(this.CMB_fmode1);
+            this.Controls.Add(this.BUT_SaveModes);
+            this.Name = "ConfigFlightModes";
+            this.Load += new System.EventHandler(this.ConfigFlightModes_Load);
+            ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit();
+            this.ResumeLayout(false);
+            this.PerformLayout();
+
+        }
+
+        #endregion
+
+        private System.Windows.Forms.CheckBox CB_simple6;
+        private System.Windows.Forms.CheckBox CB_simple5;
+        private System.Windows.Forms.CheckBox CB_simple4;
+        private System.Windows.Forms.CheckBox CB_simple3;
+        private System.Windows.Forms.CheckBox CB_simple2;
+        private System.Windows.Forms.CheckBox CB_simple1;
+        private System.Windows.Forms.Label label14;
+        private System.Windows.Forms.Label LBL_flightmodepwm;
+        private System.Windows.Forms.Label label13;
+        private System.Windows.Forms.Label lbl_currentmode;
+        private System.Windows.Forms.Label label12;
+        private System.Windows.Forms.Label label11;
+        private System.Windows.Forms.Label label10;
+        private System.Windows.Forms.Label label9;
+        private System.Windows.Forms.Label label8;
+        private System.Windows.Forms.Label label7;
+        private System.Windows.Forms.Label label6;
+        private System.Windows.Forms.ComboBox CMB_fmode6;
+        private System.Windows.Forms.Label label5;
+        private System.Windows.Forms.ComboBox CMB_fmode5;
+        private System.Windows.Forms.Label label4;
+        private System.Windows.Forms.ComboBox CMB_fmode4;
+        private System.Windows.Forms.Label label3;
+        private System.Windows.Forms.ComboBox CMB_fmode3;
+        private System.Windows.Forms.Label label2;
+        private System.Windows.Forms.ComboBox CMB_fmode2;
+        private System.Windows.Forms.Label label1;
+        private System.Windows.Forms.ComboBox CMB_fmode1;
+        private MyButton BUT_SaveModes;
+        private System.Windows.Forms.BindingSource currentStateBindingSource;
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs
new file mode 100644
index 0000000000000000000000000000000000000000..58994c233eee4810d7b0b994dad04636829f4cbb
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs
@@ -0,0 +1,226 @@
+using System;
+using System.Collections.Generic;
+using System.ComponentModel;
+using System.Drawing;
+using System.Data;
+using System.Linq;
+using System.Text;
+using System.Windows.Forms;
+using ArdupilotMega.Controls.BackstageView;
+
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    public partial class ConfigFlightModes : BackStageViewContentPanel
+    {
+        Timer timer = new Timer();
+
+        public ConfigFlightModes()
+        {
+            InitializeComponent();
+
+            timer.Tick += new EventHandler(timer_Tick);
+
+            timer.Enabled = true;
+            timer.Interval = 100;
+            timer.Start();
+        }
+
+        void timer_Tick(object sender, EventArgs e)
+        {
+            try
+            {
+                MainV2.cs.UpdateCurrentSettings(currentStateBindingSource);
+            }
+            catch { }
+
+            float pwm = 0;
+
+            if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM 
+            {
+                if (MainV2.comPort.param.ContainsKey("FLTMODE_CH"))
+                {
+                    switch ((int)(float)MainV2.comPort.param["FLTMODE_CH"])
+                    {
+                        case 5:
+                            pwm = MainV2.cs.ch5in;
+                            break;
+                        case 6:
+                            pwm = MainV2.cs.ch6in;
+                            break;
+                        case 7:
+                            pwm = MainV2.cs.ch7in;
+                            break;
+                        case 8:
+                            pwm = MainV2.cs.ch8in;
+                            break;
+                        default:
+
+                            break;
+                    }
+
+                    LBL_flightmodepwm.Text = MainV2.comPort.param["FLTMODE_CH"].ToString() + ": " + pwm.ToString();
+                }
+            }
+
+            if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) // ac2
+            {
+                pwm = MainV2.cs.ch5in;
+                LBL_flightmodepwm.Text = "5: " + MainV2.cs.ch5in.ToString();
+            }
+
+            Control[] fmodelist = new Control[] { CMB_fmode1, CMB_fmode2, CMB_fmode3, CMB_fmode4, CMB_fmode5, CMB_fmode6 };
+
+            foreach (Control ctl in fmodelist)
+            {
+                ctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
+            }
+
+            byte no = readSwitch(pwm);
+
+            fmodelist[no].BackColor = Color.Green;
+        }
+
+        // from arducopter code
+        byte readSwitch(float inpwm)
+        {
+            int pulsewidth = (int)inpwm;			// default for Arducopter
+
+            if (pulsewidth > 1230 && pulsewidth <= 1360) return 1;
+            if (pulsewidth > 1360 && pulsewidth <= 1490) return 2;
+            if (pulsewidth > 1490 && pulsewidth <= 1620) return 3;
+            if (pulsewidth > 1620 && pulsewidth <= 1749) return 4;	// Software Manual
+            if (pulsewidth >= 1750) return 5;	// Hardware Manual
+            return 0;
+        }
+
+        private void BUT_SaveModes_Click(object sender, EventArgs e)
+        {
+            try
+            {
+                if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
+                {
+                    MainV2.comPort.setParam("FLTMODE1", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode1.Text));
+                    MainV2.comPort.setParam("FLTMODE2", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode2.Text));
+                    MainV2.comPort.setParam("FLTMODE3", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode3.Text));
+                    MainV2.comPort.setParam("FLTMODE4", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode4.Text));
+                    MainV2.comPort.setParam("FLTMODE5", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode5.Text));
+                    MainV2.comPort.setParam("FLTMODE6", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode6.Text));
+                }
+                if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) // ac2
+                {
+                    MainV2.comPort.setParam("FLTMODE1", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode1.Text));
+                    MainV2.comPort.setParam("FLTMODE2", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode2.Text));
+                    MainV2.comPort.setParam("FLTMODE3", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode3.Text));
+                    MainV2.comPort.setParam("FLTMODE4", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode4.Text));
+                    MainV2.comPort.setParam("FLTMODE5", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode5.Text));
+                    MainV2.comPort.setParam("FLTMODE6", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode6.Text));
+
+                    float value = (float)(CB_simple1.Checked ? (int)SimpleMode.Simple1 : 0) + (CB_simple2.Checked ? (int)SimpleMode.Simple2 : 0) + (CB_simple3.Checked ? (int)SimpleMode.Simple3 : 0)
+                        + (CB_simple4.Checked ? (int)SimpleMode.Simple4 : 0) + (CB_simple5.Checked ? (int)SimpleMode.Simple5 : 0) + (CB_simple6.Checked ? (int)SimpleMode.Simple6 : 0);
+                    if (MainV2.comPort.param.ContainsKey("SIMPLE"))
+                        MainV2.comPort.setParam("SIMPLE", value);
+                }
+            }
+            catch { CustomMessageBox.Show("Failed to set Flight modes"); }
+            BUT_SaveModes.Text = "Complete";
+        }
+
+        [Flags]
+        public enum SimpleMode
+        {
+            None = 0,
+            Simple1 = 1,
+            Simple2 = 2,
+            Simple3 = 4,
+            Simple4 = 8,
+            Simple5 = 16,
+            Simple6 = 32,
+        }
+
+        private void ConfigFlightModes_Load(object sender, EventArgs e)
+        {
+            if (!MainV2.comPort.BaseStream.IsOpen)
+            {
+                this.Enabled = false;
+                return;
+            }
+            else
+            {
+                this.Enabled = true;
+            }
+
+            if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
+            {
+                CB_simple1.Visible = false;
+                CB_simple2.Visible = false;
+                CB_simple3.Visible = false;
+                CB_simple4.Visible = false;
+                CB_simple5.Visible = false;
+                CB_simple6.Visible = false;
+
+                CMB_fmode1.Items.Clear();
+                CMB_fmode2.Items.Clear();
+                CMB_fmode3.Items.Clear();
+                CMB_fmode4.Items.Clear();
+                CMB_fmode5.Items.Clear();
+                CMB_fmode6.Items.Clear();
+
+                CMB_fmode1.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
+                CMB_fmode2.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
+                CMB_fmode3.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
+                CMB_fmode4.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
+                CMB_fmode5.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
+                CMB_fmode6.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
+
+                try
+                {
+                    CMB_fmode1.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE1"].ToString()).ToString();
+                    CMB_fmode2.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE2"].ToString()).ToString();
+                    CMB_fmode3.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE3"].ToString()).ToString();
+                    CMB_fmode4.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE4"].ToString()).ToString();
+                    CMB_fmode5.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE5"].ToString()).ToString();
+                    CMB_fmode6.Text = Common.apmmodes.MANUAL.ToString();
+                    CMB_fmode6.Enabled = false;
+                }
+                catch { }
+            }
+            if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) // ac2
+            {
+                CMB_fmode1.Items.Clear();
+                CMB_fmode2.Items.Clear();
+                CMB_fmode3.Items.Clear();
+                CMB_fmode4.Items.Clear();
+                CMB_fmode5.Items.Clear();
+                CMB_fmode6.Items.Clear();
+
+                CMB_fmode1.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
+                CMB_fmode2.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
+                CMB_fmode3.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
+                CMB_fmode4.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
+                CMB_fmode5.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
+                CMB_fmode6.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
+
+                try
+                {
+                    CMB_fmode1.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE1"].ToString()).ToString();
+                    CMB_fmode2.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE2"].ToString()).ToString();
+                    CMB_fmode3.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE3"].ToString()).ToString();
+                    CMB_fmode4.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE4"].ToString()).ToString();
+                    CMB_fmode5.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE5"].ToString()).ToString();
+                    CMB_fmode6.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE6"].ToString()).ToString();
+                    CMB_fmode6.Enabled = true;
+
+                    int simple = int.Parse(MainV2.comPort.param["SIMPLE"].ToString());
+
+                    CB_simple1.Checked = ((simple >> 0 & 1) == 1);
+                    CB_simple2.Checked = ((simple >> 1 & 1) == 1);
+                    CB_simple3.Checked = ((simple >> 2 & 1) == 1);
+                    CB_simple4.Checked = ((simple >> 3 & 1) == 1);
+                    CB_simple5.Checked = ((simple >> 4 & 1) == 1);
+                    CB_simple6.Checked = ((simple >> 5 & 1) == 1);
+                }
+                catch { }
+            }
+        }
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.es-ES.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.es-ES.resx
new file mode 100644
index 0000000000000000000000000000000000000000..70ad73f1af84a8cec236442b9c51462353fceab5
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.es-ES.resx
@@ -0,0 +1,315 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manual</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Modo actual:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Habilitar el flujo óptico</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>NOTA: Las imágenes son sólo para su presentación</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Actual:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APMSetup</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Swash-Servo posición</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Activar Compas</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Ajuste Chásis (+ or x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modos</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Reset</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Superior</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Swash de Viaje</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manual</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Timón de Viaje</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibración del sensor de voltaje:Para calibrar el sensor, use un multímetro para medir la tensión que sale de la CES de la batería-la eliminación del circuito (se trata de cables negro y rojo en el cable de tres hilos que suministra energía a la placa APM).Luego reste 0,3 V de ese valor y entrar en él en el campo # 1 a la izquierda.</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrar Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Modo de Vuelo 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Alabeo Max</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Modo de Vuelo 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Cabeceo Max</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>por ejemplo, en grados 2 ° 3 'W es -2,3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Modo de Vuelo 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Nivel tu quad para establecer las compensaciones por defecto acel</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Modo de Vuelo 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacidad</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Declinación</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Activar Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Entrada Radio</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibración</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Modo de Vuelo 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Modo de Vuelo 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Gyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Sitio Web Declinación</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batería</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Cero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Activar Airspeed</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Restablecer los Ajustes de hardware APM</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.fr.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.fr.resx
new file mode 100644
index 0000000000000000000000000000000000000000..1bd274beea2e052315a0ab1e83d3619dcf47cbf1
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.fr.resx
@@ -0,0 +1,312 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manuel</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Mode Courant:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Activ. capteur optique</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>NOTE: images pou presentation uniquement. Fonctionnel pour Hex, Octo etc...</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Actuel:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APMSetup</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Swash-Servo position</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Activ. Boussole</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>type de châssis (+ ou x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modes</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Réinit.</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Haut</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Mouvement Swash</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manuel</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Deplac. du Gouvernail</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibration du capteur de Voltage.1. Mesurer le voltage sur APM et inscrivez-le dans la boite ci-bas.2. Mesurer le voltage de la batterie et inscrivez-le dans la boite ci-bas.3. Inscrire les ampères par volt de la documentation du capteur de courant ci-bas</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrer Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Mode de vol 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Roulis Max</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Mode de vol 2</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Tangage Max</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>en degrés eg 2° 3' W est -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Mode de vol 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Niveler l'apareil pour copensation des accels</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Mode de vol 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacité</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Déclination</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Activer Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Entrée Radio</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Mode de vol 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Mode de vol 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Gyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Matériel</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Site Web Déclination</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batterie</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zéro</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Activ. Airspeed</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>RàZ tout parametres du APM</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Moniteur</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.it-IT.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.it-IT.resx
new file mode 100644
index 0000000000000000000000000000000000000000..2b2636c8132c76e5855c9dbb2c87151786f287c3
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.it-IT.resx
@@ -0,0 +1,318 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manuale</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Modo Corrente:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Abilita Flusso ottico</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>Nota: le immagini sono sono per presentazione, funzionerà con Hexa, etc.</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevatore CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Corrente:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>Imposta APM</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Posizione del servo del piatto</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Abilita Magnetometro</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Imposta Frame (+ or x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modi</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Riavvia</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Alto</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Escursione del piatto</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manuale</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Escursione Timone</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibarzione del sensore di voltaggio:
+1. Misura il valtaggio di ingresso di APM e inseriscilo nel box sotto 
+2. Misura il voltaggio della batteria e inseriscilo nel box sotto 
+3. Dalle caratteristiche del sensore di corrente, inserisci il valore degli ampere per volt nel box qui sotto</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrazione Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Massimo</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Modo di volo 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Rollio massimo</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Modo di volo 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Passo massimo</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>in gradi es 2° 3' W is -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Modo di volo 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Livella il quad per impostare gli accelerometri</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Modo di volo 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacità</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Declinazione</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Attiva Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Ingresso Radio</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibration</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Modo di volo 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Modo di volo 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Giroscopio</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Sito Web per la Declinazione</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batteria</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Attiva Sensore Velocità</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Resetta APM ai valori di Default</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.pl.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.pl.resx
new file mode 100644
index 0000000000000000000000000000000000000000..057b9327168c6471be22139b5d017e20582de843
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.pl.resx
@@ -0,0 +1,318 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Ręczne</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Aktualny tryb:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Włącz Optical Flow</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>UWAGA: Obrazy są wyłącznie do prezentacji, działają jedynie z hexa, itp.</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Odwr. Elevon CH1</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>Aktualny PWM:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>Ustawienia APM</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Pozycja serwa płyty ster.</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Włącz kompas</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Ustawienie ramy (+ lub x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Tryby</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Reset</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Góra</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Zakres ruchu płyty sterującej</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Ręczne</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Zakres steru kierunku</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Kalibracja czujnika napięcia:
+1. Zmierz napięcie wejściowe APM i wpisz poniżej
+2. Zmierz napięcie baterii i wpisz poniżej
+3. Wpisz poniżej ilość amperów/wolt [A/V] z dokumentacji czujnika prądu</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Kalibracja radia</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Tryb lotu 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Max przechylenie</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Tryb lotu 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Max pochylenie</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>w stopniech np. 2° 3' W to -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Tryb lotu 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Wypoziomuj quada żeby stawić domyśle offsety przysp.</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Tryb lotu 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Pojemność</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Deklinacja</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Włącz sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Wejścia radia</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibration</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Tryb lotu 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Tryb lotu 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Żyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Strona www deklinacji</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Bateria</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Włącz prędkość powietrza</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Reset APM do stawień domyślnych</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx
new file mode 100644
index 0000000000000000000000000000000000000000..a4992dbe3e9e748b8e8ae8367ea3cf11e76c71ca
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx
@@ -0,0 +1,978 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
+  <data name="CB_simple6.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
+  <data name="CB_simple6.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="CB_simple6.Location" type="System.Drawing.Point, System.Drawing">
+    <value>232, 200</value>
+  </data>
+  <data name="CB_simple6.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 2, 2, 2</value>
+  </data>
+  <data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>87, 17</value>
+  </data>
+  <data name="CB_simple6.TabIndex" type="System.Int32, mscorlib">
+    <value>148</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Simple Mode</value>
+  </data>
+  <data name="&gt;&gt;CB_simple6.Name" xml:space="preserve">
+    <value>CB_simple6</value>
+  </data>
+  <data name="&gt;&gt;CB_simple6.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CB_simple6.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CB_simple6.ZOrder" xml:space="preserve">
+    <value>0</value>
+  </data>
+  <data name="CB_simple5.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="CB_simple5.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="CB_simple5.Location" type="System.Drawing.Point, System.Drawing">
+    <value>232, 173</value>
+  </data>
+  <data name="CB_simple5.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 2, 2, 2</value>
+  </data>
+  <data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>87, 17</value>
+  </data>
+  <data name="CB_simple5.TabIndex" type="System.Int32, mscorlib">
+    <value>147</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Simple Mode</value>
+  </data>
+  <data name="&gt;&gt;CB_simple5.Name" xml:space="preserve">
+    <value>CB_simple5</value>
+  </data>
+  <data name="&gt;&gt;CB_simple5.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CB_simple5.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CB_simple5.ZOrder" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple4.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="CB_simple4.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="CB_simple4.Location" type="System.Drawing.Point, System.Drawing">
+    <value>232, 146</value>
+  </data>
+  <data name="CB_simple4.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 2, 2, 2</value>
+  </data>
+  <data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>87, 17</value>
+  </data>
+  <data name="CB_simple4.TabIndex" type="System.Int32, mscorlib">
+    <value>146</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Simple Mode</value>
+  </data>
+  <data name="&gt;&gt;CB_simple4.Name" xml:space="preserve">
+    <value>CB_simple4</value>
+  </data>
+  <data name="&gt;&gt;CB_simple4.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CB_simple4.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CB_simple4.ZOrder" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="CB_simple3.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="CB_simple3.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="CB_simple3.Location" type="System.Drawing.Point, System.Drawing">
+    <value>232, 119</value>
+  </data>
+  <data name="CB_simple3.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 2, 2, 2</value>
+  </data>
+  <data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>87, 17</value>
+  </data>
+  <data name="CB_simple3.TabIndex" type="System.Int32, mscorlib">
+    <value>145</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Simple Mode</value>
+  </data>
+  <data name="&gt;&gt;CB_simple3.Name" xml:space="preserve">
+    <value>CB_simple3</value>
+  </data>
+  <data name="&gt;&gt;CB_simple3.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CB_simple3.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CB_simple3.ZOrder" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="CB_simple2.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="CB_simple2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="CB_simple2.Location" type="System.Drawing.Point, System.Drawing">
+    <value>232, 92</value>
+  </data>
+  <data name="CB_simple2.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 2, 2, 2</value>
+  </data>
+  <data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>87, 17</value>
+  </data>
+  <data name="CB_simple2.TabIndex" type="System.Int32, mscorlib">
+    <value>144</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Simple Mode</value>
+  </data>
+  <data name="&gt;&gt;CB_simple2.Name" xml:space="preserve">
+    <value>CB_simple2</value>
+  </data>
+  <data name="&gt;&gt;CB_simple2.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CB_simple2.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CB_simple2.ZOrder" xml:space="preserve">
+    <value>4</value>
+  </data>
+  <data name="CB_simple1.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="CB_simple1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="CB_simple1.Location" type="System.Drawing.Point, System.Drawing">
+    <value>232, 65</value>
+  </data>
+  <data name="CB_simple1.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 2, 2, 2</value>
+  </data>
+  <data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>87, 17</value>
+  </data>
+  <data name="CB_simple1.TabIndex" type="System.Int32, mscorlib">
+    <value>143</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Simple Mode</value>
+  </data>
+  <data name="&gt;&gt;CB_simple1.Name" xml:space="preserve">
+    <value>CB_simple1</value>
+  </data>
+  <data name="&gt;&gt;CB_simple1.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CB_simple1.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CB_simple1.ZOrder" xml:space="preserve">
+    <value>5</value>
+  </data>
+  <data name="label14.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label14.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label14.Location" type="System.Drawing.Point, System.Drawing">
+    <value>94, 32</value>
+  </data>
+  <data name="label14.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 13</value>
+  </data>
+  <data name="label14.TabIndex" type="System.Int32, mscorlib">
+    <value>142</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>Current PWM:</value>
+  </data>
+  <data name="&gt;&gt;label14.Name" xml:space="preserve">
+    <value>label14</value>
+  </data>
+  <data name="&gt;&gt;label14.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label14.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label14.ZOrder" xml:space="preserve">
+    <value>6</value>
+  </data>
+  <data name="LBL_flightmodepwm.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="LBL_flightmodepwm.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="LBL_flightmodepwm.Location" type="System.Drawing.Point, System.Drawing">
+    <value>174, 32</value>
+  </data>
+  <data name="LBL_flightmodepwm.Size" type="System.Drawing.Size, System.Drawing">
+    <value>13, 13</value>
+  </data>
+  <data name="LBL_flightmodepwm.TabIndex" type="System.Int32, mscorlib">
+    <value>141</value>
+  </data>
+  <data name="LBL_flightmodepwm.Text" xml:space="preserve">
+    <value>0</value>
+  </data>
+  <data name="&gt;&gt;LBL_flightmodepwm.Name" xml:space="preserve">
+    <value>LBL_flightmodepwm</value>
+  </data>
+  <data name="&gt;&gt;LBL_flightmodepwm.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;LBL_flightmodepwm.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;LBL_flightmodepwm.ZOrder" xml:space="preserve">
+    <value>7</value>
+  </data>
+  <data name="label13.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label13.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label13.Location" type="System.Drawing.Point, System.Drawing">
+    <value>94, 15</value>
+  </data>
+  <data name="label13.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 13</value>
+  </data>
+  <data name="label13.TabIndex" type="System.Int32, mscorlib">
+    <value>140</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Current Mode:</value>
+  </data>
+  <data name="&gt;&gt;label13.Name" xml:space="preserve">
+    <value>label13</value>
+  </data>
+  <data name="&gt;&gt;label13.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label13.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label13.ZOrder" xml:space="preserve">
+    <value>8</value>
+  </data>
+  <data name="lbl_currentmode.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <metadata name="currentStateBindingSource.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
+    <value>17, 17</value>
+  </metadata>
+  <data name="lbl_currentmode.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="lbl_currentmode.Location" type="System.Drawing.Point, System.Drawing">
+    <value>174, 15</value>
+  </data>
+  <data name="lbl_currentmode.Size" type="System.Drawing.Size, System.Drawing">
+    <value>42, 13</value>
+  </data>
+  <data name="lbl_currentmode.TabIndex" type="System.Int32, mscorlib">
+    <value>139</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manual</value>
+  </data>
+  <data name="&gt;&gt;lbl_currentmode.Name" xml:space="preserve">
+    <value>lbl_currentmode</value>
+  </data>
+  <data name="&gt;&gt;lbl_currentmode.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;lbl_currentmode.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;lbl_currentmode.ZOrder" xml:space="preserve">
+    <value>9</value>
+  </data>
+  <data name="label12.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label12.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label12.Location" type="System.Drawing.Point, System.Drawing">
+    <value>358, 66</value>
+  </data>
+  <data name="label12.Size" type="System.Drawing.Size, System.Drawing">
+    <value>76, 13</value>
+  </data>
+  <data name="label12.TabIndex" type="System.Int32, mscorlib">
+    <value>138</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="&gt;&gt;label12.Name" xml:space="preserve">
+    <value>label12</value>
+  </data>
+  <data name="&gt;&gt;label12.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label12.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label12.ZOrder" xml:space="preserve">
+    <value>10</value>
+  </data>
+  <data name="label11.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label11.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label11.Location" type="System.Drawing.Point, System.Drawing">
+    <value>358, 201</value>
+  </data>
+  <data name="label11.Size" type="System.Drawing.Size, System.Drawing">
+    <value>70, 13</value>
+  </data>
+  <data name="label11.TabIndex" type="System.Int32, mscorlib">
+    <value>137</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="&gt;&gt;label11.Name" xml:space="preserve">
+    <value>label11</value>
+  </data>
+  <data name="&gt;&gt;label11.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label11.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label11.ZOrder" xml:space="preserve">
+    <value>11</value>
+  </data>
+  <data name="label10.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label10.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label10.Location" type="System.Drawing.Point, System.Drawing">
+    <value>358, 174</value>
+  </data>
+  <data name="label10.Size" type="System.Drawing.Size, System.Drawing">
+    <value>94, 13</value>
+  </data>
+  <data name="label10.TabIndex" type="System.Int32, mscorlib">
+    <value>136</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="&gt;&gt;label10.Name" xml:space="preserve">
+    <value>label10</value>
+  </data>
+  <data name="&gt;&gt;label10.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label10.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label10.ZOrder" xml:space="preserve">
+    <value>12</value>
+  </data>
+  <data name="label9.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label9.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label9.Location" type="System.Drawing.Point, System.Drawing">
+    <value>358, 147</value>
+  </data>
+  <data name="label9.Size" type="System.Drawing.Size, System.Drawing">
+    <value>94, 13</value>
+  </data>
+  <data name="label9.TabIndex" type="System.Int32, mscorlib">
+    <value>135</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="&gt;&gt;label9.Name" xml:space="preserve">
+    <value>label9</value>
+  </data>
+  <data name="&gt;&gt;label9.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label9.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label9.ZOrder" xml:space="preserve">
+    <value>13</value>
+  </data>
+  <data name="label8.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label8.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label8.Location" type="System.Drawing.Point, System.Drawing">
+    <value>358, 120</value>
+  </data>
+  <data name="label8.Size" type="System.Drawing.Size, System.Drawing">
+    <value>94, 13</value>
+  </data>
+  <data name="label8.TabIndex" type="System.Int32, mscorlib">
+    <value>134</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="&gt;&gt;label8.Name" xml:space="preserve">
+    <value>label8</value>
+  </data>
+  <data name="&gt;&gt;label8.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label8.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label8.ZOrder" xml:space="preserve">
+    <value>14</value>
+  </data>
+  <data name="label7.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label7.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label7.Location" type="System.Drawing.Point, System.Drawing">
+    <value>358, 93</value>
+  </data>
+  <data name="label7.Size" type="System.Drawing.Size, System.Drawing">
+    <value>94, 13</value>
+  </data>
+  <data name="label7.TabIndex" type="System.Int32, mscorlib">
+    <value>133</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="&gt;&gt;label7.Name" xml:space="preserve">
+    <value>label7</value>
+  </data>
+  <data name="&gt;&gt;label7.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label7.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label7.ZOrder" xml:space="preserve">
+    <value>15</value>
+  </data>
+  <data name="label6.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label6.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label6.Location" type="System.Drawing.Point, System.Drawing">
+    <value>20, 201</value>
+  </data>
+  <data name="label6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>71, 13</value>
+  </data>
+  <data name="label6.TabIndex" type="System.Int32, mscorlib">
+    <value>131</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Flight Mode 6</value>
+  </data>
+  <data name="&gt;&gt;label6.Name" xml:space="preserve">
+    <value>label6</value>
+  </data>
+  <data name="&gt;&gt;label6.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label6.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label6.ZOrder" xml:space="preserve">
+    <value>16</value>
+  </data>
+  <data name="CMB_fmode6.Location" type="System.Drawing.Point, System.Drawing">
+    <value>97, 198</value>
+  </data>
+  <data name="CMB_fmode6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>121, 21</value>
+  </data>
+  <data name="CMB_fmode6.TabIndex" type="System.Int32, mscorlib">
+    <value>130</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode6.Name" xml:space="preserve">
+    <value>CMB_fmode6</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode6.Type" xml:space="preserve">
+    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode6.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode6.ZOrder" xml:space="preserve">
+    <value>17</value>
+  </data>
+  <data name="label5.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label5.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label5.Location" type="System.Drawing.Point, System.Drawing">
+    <value>20, 174</value>
+  </data>
+  <data name="label5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>71, 13</value>
+  </data>
+  <data name="label5.TabIndex" type="System.Int32, mscorlib">
+    <value>129</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Flight Mode 5</value>
+  </data>
+  <data name="&gt;&gt;label5.Name" xml:space="preserve">
+    <value>label5</value>
+  </data>
+  <data name="&gt;&gt;label5.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label5.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label5.ZOrder" xml:space="preserve">
+    <value>18</value>
+  </data>
+  <data name="CMB_fmode5.Location" type="System.Drawing.Point, System.Drawing">
+    <value>97, 171</value>
+  </data>
+  <data name="CMB_fmode5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>121, 21</value>
+  </data>
+  <data name="CMB_fmode5.TabIndex" type="System.Int32, mscorlib">
+    <value>128</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode5.Name" xml:space="preserve">
+    <value>CMB_fmode5</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode5.Type" xml:space="preserve">
+    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode5.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode5.ZOrder" xml:space="preserve">
+    <value>19</value>
+  </data>
+  <data name="label4.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label4.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label4.Location" type="System.Drawing.Point, System.Drawing">
+    <value>20, 147</value>
+  </data>
+  <data name="label4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>71, 13</value>
+  </data>
+  <data name="label4.TabIndex" type="System.Int32, mscorlib">
+    <value>127</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Flight Mode 4</value>
+  </data>
+  <data name="&gt;&gt;label4.Name" xml:space="preserve">
+    <value>label4</value>
+  </data>
+  <data name="&gt;&gt;label4.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label4.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label4.ZOrder" xml:space="preserve">
+    <value>20</value>
+  </data>
+  <data name="CMB_fmode4.Location" type="System.Drawing.Point, System.Drawing">
+    <value>97, 144</value>
+  </data>
+  <data name="CMB_fmode4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>121, 21</value>
+  </data>
+  <data name="CMB_fmode4.TabIndex" type="System.Int32, mscorlib">
+    <value>126</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode4.Name" xml:space="preserve">
+    <value>CMB_fmode4</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode4.Type" xml:space="preserve">
+    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode4.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode4.ZOrder" xml:space="preserve">
+    <value>21</value>
+  </data>
+  <data name="label3.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label3.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label3.Location" type="System.Drawing.Point, System.Drawing">
+    <value>20, 120</value>
+  </data>
+  <data name="label3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>71, 13</value>
+  </data>
+  <data name="label3.TabIndex" type="System.Int32, mscorlib">
+    <value>125</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Flight Mode 3</value>
+  </data>
+  <data name="&gt;&gt;label3.Name" xml:space="preserve">
+    <value>label3</value>
+  </data>
+  <data name="&gt;&gt;label3.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label3.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label3.ZOrder" xml:space="preserve">
+    <value>22</value>
+  </data>
+  <data name="CMB_fmode3.Location" type="System.Drawing.Point, System.Drawing">
+    <value>97, 117</value>
+  </data>
+  <data name="CMB_fmode3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>121, 21</value>
+  </data>
+  <data name="CMB_fmode3.TabIndex" type="System.Int32, mscorlib">
+    <value>124</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode3.Name" xml:space="preserve">
+    <value>CMB_fmode3</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode3.Type" xml:space="preserve">
+    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode3.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode3.ZOrder" xml:space="preserve">
+    <value>23</value>
+  </data>
+  <data name="label2.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label2.Location" type="System.Drawing.Point, System.Drawing">
+    <value>20, 93</value>
+  </data>
+  <data name="label2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>71, 13</value>
+  </data>
+  <data name="label2.TabIndex" type="System.Int32, mscorlib">
+    <value>123</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Flight Mode 2</value>
+  </data>
+  <data name="&gt;&gt;label2.Name" xml:space="preserve">
+    <value>label2</value>
+  </data>
+  <data name="&gt;&gt;label2.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label2.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label2.ZOrder" xml:space="preserve">
+    <value>24</value>
+  </data>
+  <data name="CMB_fmode2.Location" type="System.Drawing.Point, System.Drawing">
+    <value>97, 90</value>
+  </data>
+  <data name="CMB_fmode2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>121, 21</value>
+  </data>
+  <data name="CMB_fmode2.TabIndex" type="System.Int32, mscorlib">
+    <value>122</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode2.Name" xml:space="preserve">
+    <value>CMB_fmode2</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode2.Type" xml:space="preserve">
+    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode2.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode2.ZOrder" xml:space="preserve">
+    <value>25</value>
+  </data>
+  <data name="label1.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label1.Location" type="System.Drawing.Point, System.Drawing">
+    <value>20, 66</value>
+  </data>
+  <data name="label1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>71, 13</value>
+  </data>
+  <data name="label1.TabIndex" type="System.Int32, mscorlib">
+    <value>121</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Flight Mode 1</value>
+  </data>
+  <data name="&gt;&gt;label1.Name" xml:space="preserve">
+    <value>label1</value>
+  </data>
+  <data name="&gt;&gt;label1.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label1.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label1.ZOrder" xml:space="preserve">
+    <value>26</value>
+  </data>
+  <data name="CMB_fmode1.Location" type="System.Drawing.Point, System.Drawing">
+    <value>97, 63</value>
+  </data>
+  <data name="CMB_fmode1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>121, 21</value>
+  </data>
+  <data name="CMB_fmode1.TabIndex" type="System.Int32, mscorlib">
+    <value>120</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode1.Name" xml:space="preserve">
+    <value>CMB_fmode1</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode1.Type" xml:space="preserve">
+    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode1.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CMB_fmode1.ZOrder" xml:space="preserve">
+    <value>27</value>
+  </data>
+  <data name="BUT_SaveModes.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="BUT_SaveModes.Location" type="System.Drawing.Point, System.Drawing">
+    <value>97, 225</value>
+  </data>
+  <data name="BUT_SaveModes.Size" type="System.Drawing.Size, System.Drawing">
+    <value>121, 23</value>
+  </data>
+  <data name="BUT_SaveModes.TabIndex" type="System.Int32, mscorlib">
+    <value>132</value>
+  </data>
+  <data name="BUT_SaveModes.Text" xml:space="preserve">
+    <value>Save Modes</value>
+  </data>
+  <data name="&gt;&gt;BUT_SaveModes.Name" xml:space="preserve">
+    <value>BUT_SaveModes</value>
+  </data>
+  <data name="&gt;&gt;BUT_SaveModes.Type" xml:space="preserve">
+    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;BUT_SaveModes.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;BUT_SaveModes.ZOrder" xml:space="preserve">
+    <value>28</value>
+  </data>
+  <metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
+    <value>True</value>
+  </metadata>
+  <data name="$this.AutoScaleDimensions" type="System.Drawing.SizeF, System.Drawing">
+    <value>6, 13</value>
+  </data>
+  <data name="$this.Size" type="System.Drawing.Size, System.Drawing">
+    <value>500, 270</value>
+  </data>
+  <data name="&gt;&gt;currentStateBindingSource.Name" xml:space="preserve">
+    <value>currentStateBindingSource</value>
+  </data>
+  <data name="&gt;&gt;currentStateBindingSource.Type" xml:space="preserve">
+    <value>System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;$this.Name" xml:space="preserve">
+    <value>ConfigFlightModes</value>
+  </data>
+  <data name="&gt;&gt;$this.Type" xml:space="preserve">
+    <value>System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.zh-Hans.resx
new file mode 100644
index 0000000000000000000000000000000000000000..f96892c423b112b28127ad582686f33464b57c5b
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.zh-Hans.resx
@@ -0,0 +1,496 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>遥控输入</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>模式</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>硬件</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>电池</value>
+  </data>
+  <data name="tabHeli.Text" xml:space="preserve">
+    <value>AC2 直升机</value>
+  </data>
+  <data name="groupBoxElevons.Text" xml:space="preserve">
+    <value>上降副翼 (Elevon) 配置</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="CHK_elevonch2rev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>115, 17</value>
+  </data>
+  <data name="CHK_elevonch2rev.Text" xml:space="preserve">
+    <value>Elevons CH2 逆转</value>
+  </data>
+  <data name="CHK_elevonrev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>91, 17</value>
+  </data>
+  <data name="CHK_elevonrev.Text" xml:space="preserve">
+    <value>Elevons 逆转</value>
+  </data>
+  <data name="CHK_elevonch1rev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>115, 17</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 逆转</value>
+  </data>
+  <data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch3.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch4.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch2.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch1.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>校准遥控</value>
+  </data>
+  <data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="label14.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>当前 PWM:</value>
+  </data>
+  <data name="label13.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>当前模式:</value>
+  </data>
+  <data name="label6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>飞行模式 6</value>
+  </data>
+  <data name="label5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>飞行模式 5</value>
+  </data>
+  <data name="label4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>飞行模式 4</value>
+  </data>
+  <data name="label3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>飞行模式 3</value>
+  </data>
+  <data name="label2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>飞行模式 2</value>
+  </data>
+  <data name="label1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>飞行模式 1</value>
+  </data>
+  <data name="BUT_SaveModes.Text" xml:space="preserve">
+    <value>保存模式</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>十进制, 2° 3' W 就是 -2.3</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>启用光流</value>
+  </data>
+  <data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
+    <value>67, 13</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>磁偏角网站</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>磁偏角</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>启用空速计</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>启用声纳</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>启用罗盘</value>
+  </data>
+  <data name="label31.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label31.Text" xml:space="preserve">
+    <value>输入电压:</value>
+  </data>
+  <data name="label32.Size" type="System.Drawing.Size, System.Drawing">
+    <value>94, 13</value>
+  </data>
+  <data name="label32.Text" xml:space="preserve">
+    <value>测量的电池电压:</value>
+  </data>
+  <data name="label33.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label33.Text" xml:space="preserve">
+    <value>电池电压:</value>
+  </data>
+  <data name="label34.Size" type="System.Drawing.Size, System.Drawing">
+    <value>52, 13</value>
+  </data>
+  <data name="label34.Text" xml:space="preserve">
+    <value>分 压 比:</value>
+  </data>
+  <data name="label35.Size" type="System.Drawing.Size, System.Drawing">
+    <value>63, 13</value>
+  </data>
+  <data name="label35.Text" xml:space="preserve">
+    <value>安培/伏特:</value>
+  </data>
+  <data name="label47.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 18</value>
+  </data>
+  <data name="label47.Text" xml:space="preserve">
+    <value>传感器</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>电压传感器校准:
+1. 测量APM输入电压,输入到下方的文本框中
+2. 测量电池电压,输入到下方的文本框中
+3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中</value>
+  </data>
+  <data name="label29.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>容量</value>
+  </data>
+  <data name="label30.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 13</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>监控器</value>
+  </data>
+  <data name="label28.Size" type="System.Drawing.Size, System.Drawing">
+    <value>175, 13</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>设置水平面的默认加速度计偏移</value>
+  </data>
+  <data name="label16.Size" type="System.Drawing.Size, System.Drawing">
+    <value>261, 13</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>注: 图片只是用于展示,设置可以用于六轴等机架</value>
+  </data>
+  <data name="label15.Size" type="System.Drawing.Size, System.Drawing">
+    <value>93, 13</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>机架设置 (+ 或 x)</value>
+  </data>
+  <data name="BUT_levelac2.Text" xml:space="preserve">
+    <value>找平</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>手动</value>
+  </data>
+  <data name="BUT_swash_manual.Text" xml:space="preserve">
+    <value>手动</value>
+  </data>
+  <data name="label46.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label46.Text" xml:space="preserve">
+    <value>感度</value>
+  </data>
+  <data name="label45.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label45.Text" xml:space="preserve">
+    <value>启用</value>
+  </data>
+  <data name="label44.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label44.Text" xml:space="preserve">
+    <value>微调</value>
+  </data>
+  <data name="label43.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label43.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="label42.Size" type="System.Drawing.Size, System.Drawing">
+    <value>43, 13</value>
+  </data>
+  <data name="label42.Text" xml:space="preserve">
+    <value>方向舵</value>
+  </data>
+  <data name="label24.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>最大</value>
+  </data>
+  <data name="label40.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label40.Text" xml:space="preserve">
+    <value>最小</value>
+  </data>
+  <data name="label41.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label41.Text" xml:space="preserve">
+    <value>最低</value>
+  </data>
+  <data name="label21.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>最高</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>0度</value>
+  </data>
+  <data name="label39.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label39.Text" xml:space="preserve">
+    <value>微调</value>
+  </data>
+  <data name="label38.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label38.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="label37.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label37.Text" xml:space="preserve">
+    <value>位置</value>
+  </data>
+  <data name="label36.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label36.Text" xml:space="preserve">
+    <value>舵机</value>
+  </data>
+  <data name="label26.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>最大俯仰</value>
+  </data>
+  <data name="label25.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>最大侧倾</value>
+  </data>
+  <data name="label23.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>舵机行程</value>
+  </data>
+  <data name="label22.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>斜盘水平微调</value>
+  </data>
+  <data name="label17.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>斜盘舵机位置</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>重置</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>重置 APM 为默认设置</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APM设置</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.zh-TW.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.zh-TW.resx
new file mode 100644
index 0000000000000000000000000000000000000000..0c03fbf8ed6bd5befc34246175bf1adf106cce43
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.zh-TW.resx
@@ -0,0 +1,460 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>重置</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>遙控輸入</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>模式</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>硬件</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>電池</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>重置 APM 為默認設置</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch3.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch4.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch2.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch1.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>校準遙控</value>
+  </data>
+  <data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="label14.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>當前 PWM:</value>
+  </data>
+  <data name="label13.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>當前模式:</value>
+  </data>
+  <data name="label6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>飛行模式 6</value>
+  </data>
+  <data name="label5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>飛行模式 5</value>
+  </data>
+  <data name="label4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>飛行模式 4</value>
+  </data>
+  <data name="label3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>飛行模式 3</value>
+  </data>
+  <data name="label2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>飛行模式 2</value>
+  </data>
+  <data name="label1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>飛行模式 1</value>
+  </data>
+  <data name="BUT_SaveModes.Text" xml:space="preserve">
+    <value>保存模式</value>
+  </data>
+  <data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
+    <value>67, 13</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>磁偏角網站</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>磁偏角</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>啟用空速計</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>啟用聲納</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>啟用羅盤</value>
+  </data>
+  <data name="label35.Size" type="System.Drawing.Size, System.Drawing">
+    <value>63, 13</value>
+  </data>
+  <data name="label35.Text" xml:space="preserve">
+    <value>安培/伏特:</value>
+  </data>
+  <data name="label34.Size" type="System.Drawing.Size, System.Drawing">
+    <value>52, 13</value>
+  </data>
+  <data name="label34.Text" xml:space="preserve">
+    <value>分 壓 比:</value>
+  </data>
+  <data name="label33.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label33.Text" xml:space="preserve">
+    <value>電池電壓:</value>
+  </data>
+  <data name="label32.Size" type="System.Drawing.Size, System.Drawing">
+    <value>94, 13</value>
+  </data>
+  <data name="label32.Text" xml:space="preserve">
+    <value>測量的電池電壓:</value>
+  </data>
+  <data name="label31.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label31.Text" xml:space="preserve">
+    <value>輸入電壓:</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>電壓傳感器校準:
+1. 測量APM輸入電壓,輸入到下方的文本框中
+2. 測量電池電壓,輸入到下方的文本框中
+3. 從當前的傳感器的數據表中找到安培/伏特,輸入到下方的文本框中</value>
+  </data>
+  <data name="label29.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>容量</value>
+  </data>
+  <data name="label30.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 13</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>監控器</value>
+  </data>
+  <data name="label28.Size" type="System.Drawing.Size, System.Drawing">
+    <value>175, 13</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>設置水平面的默認加速度計偏移</value>
+  </data>
+  <data name="label16.Size" type="System.Drawing.Size, System.Drawing">
+    <value>261, 13</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>注: 圖片只是用於展示,設置可以用於六軸等機架</value>
+  </data>
+  <data name="label15.Size" type="System.Drawing.Size, System.Drawing">
+    <value>93, 13</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>機架設置 (+ 或 x)</value>
+  </data>
+  <data name="BUT_levelac2.Text" xml:space="preserve">
+    <value>找平</value>
+  </data>
+  <data name="label46.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label46.Text" xml:space="preserve">
+    <value>感度</value>
+  </data>
+  <data name="label45.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label45.Text" xml:space="preserve">
+    <value>啟用</value>
+  </data>
+  <data name="label44.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label44.Text" xml:space="preserve">
+    <value>微調</value>
+  </data>
+  <data name="label43.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label43.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="label42.Size" type="System.Drawing.Size, System.Drawing">
+    <value>43, 13</value>
+  </data>
+  <data name="label42.Text" xml:space="preserve">
+    <value>方向舵</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>手動</value>
+  </data>
+  <data name="label24.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>最大</value>
+  </data>
+  <data name="label40.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label40.Text" xml:space="preserve">
+    <value>最小</value>
+  </data>
+  <data name="BUT_swash_manual.Text" xml:space="preserve">
+    <value>手動</value>
+  </data>
+  <data name="label41.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label41.Text" xml:space="preserve">
+    <value>最低</value>
+  </data>
+  <data name="label21.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>最高</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>0度</value>
+  </data>
+  <data name="label39.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label39.Text" xml:space="preserve">
+    <value>微調</value>
+  </data>
+  <data name="label38.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label38.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="label37.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label37.Text" xml:space="preserve">
+    <value>位置</value>
+  </data>
+  <data name="label36.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label36.Text" xml:space="preserve">
+    <value>舵機</value>
+  </data>
+  <data name="label26.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>最大俯仰</value>
+  </data>
+  <data name="label25.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>最大側傾</value>
+  </data>
+  <data name="label23.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>舵機行程</value>
+  </data>
+  <data name="label22.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>斜盤水平微調</value>
+  </data>
+  <data name="label17.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>斜盤舵機位置</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APM設置</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs
new file mode 100644
index 0000000000000000000000000000000000000000..fcd141dac8825120a21e4882bc7a3f27938b810b
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs
@@ -0,0 +1,202 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    partial class ConfigHardwareOptions
+    {
+        /// <summary> 
+        /// Required designer variable.
+        /// </summary>
+        private System.ComponentModel.IContainer components = null;
+
+        /// <summary> 
+        /// Clean up any resources being used.
+        /// </summary>
+        /// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
+        protected override void Dispose(bool disposing)
+        {
+            if (disposing && (components != null))
+            {
+                components.Dispose();
+            }
+            base.Dispose(disposing);
+        }
+
+        #region Component Designer generated code
+
+        /// <summary> 
+        /// Required method for Designer support - do not modify 
+        /// the contents of this method with the code editor.
+        /// </summary>
+        private void InitializeComponent()
+        {
+            System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigHardwareOptions));
+            this.BUT_MagCalibration = new ArdupilotMega.MyButton();
+            this.label27 = new System.Windows.Forms.Label();
+            this.CMB_sonartype = new System.Windows.Forms.ComboBox();
+            this.CHK_enableoptflow = new System.Windows.Forms.CheckBox();
+            this.pictureBox2 = new System.Windows.Forms.PictureBox();
+            this.linkLabelmagdec = new System.Windows.Forms.LinkLabel();
+            this.label100 = new System.Windows.Forms.Label();
+            this.TXT_declination = new System.Windows.Forms.TextBox();
+            this.CHK_enableairspeed = new System.Windows.Forms.CheckBox();
+            this.CHK_enablesonar = new System.Windows.Forms.CheckBox();
+            this.CHK_enablecompass = new System.Windows.Forms.CheckBox();
+            this.pictureBox4 = new System.Windows.Forms.PictureBox();
+            this.pictureBox3 = new System.Windows.Forms.PictureBox();
+            this.pictureBox1 = new System.Windows.Forms.PictureBox();
+            ((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.pictureBox4)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.pictureBox3)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).BeginInit();
+            this.SuspendLayout();
+            // 
+            // BUT_MagCalibration
+            // 
+            resources.ApplyResources(this.BUT_MagCalibration, "BUT_MagCalibration");
+            this.BUT_MagCalibration.Name = "BUT_MagCalibration";
+            this.BUT_MagCalibration.UseVisualStyleBackColor = true;
+            this.BUT_MagCalibration.Click += new System.EventHandler(this.BUT_MagCalibration_Click);
+            // 
+            // label27
+            // 
+            resources.ApplyResources(this.label27, "label27");
+            this.label27.Name = "label27";
+            // 
+            // CMB_sonartype
+            // 
+            this.CMB_sonartype.FormattingEnabled = true;
+            this.CMB_sonartype.Items.AddRange(new object[] {
+            resources.GetString("CMB_sonartype.Items"),
+            resources.GetString("CMB_sonartype.Items1"),
+            resources.GetString("CMB_sonartype.Items2")});
+            resources.ApplyResources(this.CMB_sonartype, "CMB_sonartype");
+            this.CMB_sonartype.Name = "CMB_sonartype";
+            this.CMB_sonartype.SelectedIndexChanged += new System.EventHandler(this.CMB_sonartype_SelectedIndexChanged);
+            // 
+            // CHK_enableoptflow
+            // 
+            resources.ApplyResources(this.CHK_enableoptflow, "CHK_enableoptflow");
+            this.CHK_enableoptflow.Name = "CHK_enableoptflow";
+            this.CHK_enableoptflow.UseVisualStyleBackColor = true;
+            this.CHK_enableoptflow.CheckedChanged += new System.EventHandler(this.CHK_enableoptflow_CheckedChanged);
+            // 
+            // pictureBox2
+            // 
+            this.pictureBox2.BackColor = System.Drawing.Color.White;
+            this.pictureBox2.BackgroundImage = global::ArdupilotMega.Properties.Resources.opticalflow;
+            resources.ApplyResources(this.pictureBox2, "pictureBox2");
+            this.pictureBox2.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle;
+            this.pictureBox2.Name = "pictureBox2";
+            this.pictureBox2.TabStop = false;
+            // 
+            // linkLabelmagdec
+            // 
+            resources.ApplyResources(this.linkLabelmagdec, "linkLabelmagdec");
+            this.linkLabelmagdec.Name = "linkLabelmagdec";
+            this.linkLabelmagdec.TabStop = true;
+            this.linkLabelmagdec.LinkClicked += new System.Windows.Forms.LinkLabelLinkClickedEventHandler(this.linkLabel1_LinkClicked);
+            // 
+            // label100
+            // 
+            resources.ApplyResources(this.label100, "label100");
+            this.label100.Name = "label100";
+            // 
+            // TXT_declination
+            // 
+            resources.ApplyResources(this.TXT_declination, "TXT_declination");
+            this.TXT_declination.Name = "TXT_declination";
+            this.TXT_declination.Validated += new System.EventHandler(this.TXT_declination_Validated);
+            // 
+            // CHK_enableairspeed
+            // 
+            resources.ApplyResources(this.CHK_enableairspeed, "CHK_enableairspeed");
+            this.CHK_enableairspeed.Name = "CHK_enableairspeed";
+            this.CHK_enableairspeed.UseVisualStyleBackColor = true;
+            this.CHK_enableairspeed.CheckedChanged += new System.EventHandler(this.CHK_enableairspeed_CheckedChanged);
+            // 
+            // CHK_enablesonar
+            // 
+            resources.ApplyResources(this.CHK_enablesonar, "CHK_enablesonar");
+            this.CHK_enablesonar.Name = "CHK_enablesonar";
+            this.CHK_enablesonar.UseVisualStyleBackColor = true;
+            this.CHK_enablesonar.CheckedChanged += new System.EventHandler(this.CHK_enablesonar_CheckedChanged);
+            // 
+            // CHK_enablecompass
+            // 
+            resources.ApplyResources(this.CHK_enablecompass, "CHK_enablecompass");
+            this.CHK_enablecompass.Name = "CHK_enablecompass";
+            this.CHK_enablecompass.UseVisualStyleBackColor = true;
+            this.CHK_enablecompass.CheckedChanged += new System.EventHandler(this.CHK_enablecompass_CheckedChanged);
+            // 
+            // pictureBox4
+            // 
+            this.pictureBox4.BackColor = System.Drawing.Color.White;
+            this.pictureBox4.BackgroundImage = global::ArdupilotMega.Properties.Resources.airspeed;
+            resources.ApplyResources(this.pictureBox4, "pictureBox4");
+            this.pictureBox4.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle;
+            this.pictureBox4.Name = "pictureBox4";
+            this.pictureBox4.TabStop = false;
+            // 
+            // pictureBox3
+            // 
+            this.pictureBox3.BackColor = System.Drawing.Color.White;
+            this.pictureBox3.BackgroundImage = global::ArdupilotMega.Properties.Resources.sonar;
+            resources.ApplyResources(this.pictureBox3, "pictureBox3");
+            this.pictureBox3.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle;
+            this.pictureBox3.Name = "pictureBox3";
+            this.pictureBox3.TabStop = false;
+            // 
+            // pictureBox1
+            // 
+            this.pictureBox1.BackgroundImage = global::ArdupilotMega.Properties.Resources.compass;
+            resources.ApplyResources(this.pictureBox1, "pictureBox1");
+            this.pictureBox1.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle;
+            this.pictureBox1.Name = "pictureBox1";
+            this.pictureBox1.TabStop = false;
+            // 
+            // ConfigHardwareOptions
+            // 
+            resources.ApplyResources(this, "$this");
+            this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+            this.Controls.Add(this.BUT_MagCalibration);
+            this.Controls.Add(this.label27);
+            this.Controls.Add(this.CMB_sonartype);
+            this.Controls.Add(this.CHK_enableoptflow);
+            this.Controls.Add(this.pictureBox2);
+            this.Controls.Add(this.linkLabelmagdec);
+            this.Controls.Add(this.label100);
+            this.Controls.Add(this.TXT_declination);
+            this.Controls.Add(this.CHK_enableairspeed);
+            this.Controls.Add(this.CHK_enablesonar);
+            this.Controls.Add(this.CHK_enablecompass);
+            this.Controls.Add(this.pictureBox4);
+            this.Controls.Add(this.pictureBox3);
+            this.Controls.Add(this.pictureBox1);
+            this.Name = "ConfigHardwareOptions";
+            this.Load += new System.EventHandler(this.ConfigHardwareOptions_Load);
+            ((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.pictureBox4)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.pictureBox3)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).EndInit();
+            this.ResumeLayout(false);
+            this.PerformLayout();
+
+        }
+
+        #endregion
+
+        private MyButton BUT_MagCalibration;
+        private System.Windows.Forms.Label label27;
+        private System.Windows.Forms.ComboBox CMB_sonartype;
+        private System.Windows.Forms.CheckBox CHK_enableoptflow;
+        private System.Windows.Forms.PictureBox pictureBox2;
+        private System.Windows.Forms.LinkLabel linkLabelmagdec;
+        private System.Windows.Forms.Label label100;
+        private System.Windows.Forms.TextBox TXT_declination;
+        private System.Windows.Forms.CheckBox CHK_enableairspeed;
+        private System.Windows.Forms.CheckBox CHK_enablesonar;
+        private System.Windows.Forms.CheckBox CHK_enablecompass;
+        private System.Windows.Forms.PictureBox pictureBox4;
+        private System.Windows.Forms.PictureBox pictureBox3;
+        private System.Windows.Forms.PictureBox pictureBox1;
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs
new file mode 100644
index 0000000000000000000000000000000000000000..470cd0902623664b6571e1977d5846f80ef6234f
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs
@@ -0,0 +1,271 @@
+using System;
+using System.Collections.Generic;
+using System.ComponentModel;
+using System.Drawing;
+using System.Data;
+using System.Linq;
+using System.Text;
+using System.Windows.Forms;
+using ArdupilotMega.Controls.BackstageView;
+
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    public partial class ConfigHardwareOptions : BackStageViewContentPanel
+    {
+        bool startup = false;
+
+        const float rad2deg = (float)(180 / Math.PI);
+        const float deg2rad = (float)(1.0 / rad2deg);
+
+        public ConfigHardwareOptions()
+        {
+            InitializeComponent();
+        }
+
+        private void BUT_MagCalibration_Click(object sender, EventArgs e)
+        {
+            if (DialogResult.Yes == CustomMessageBox.Show("Use live data, or a log\n\nYes for Live data", "Mag Calibration", MessageBoxButtons.YesNo))
+            {
+                List<Tuple<float, float, float>> data = new List<Tuple<float, float, float>>();
+
+                byte backupratesens = MainV2.cs.ratesensors;
+
+                MainV2.cs.ratesensors = 10;
+
+                MainV2.comPort.requestDatastream((byte)MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.cs.ratesensors); // mag captures at 10 hz
+
+                CustomMessageBox.Show("Data will be collected for 30 seconds, Please click ok and move the apm around all axises");
+
+                DateTime deadline = DateTime.Now.AddSeconds(30);
+
+                float oldmx = 0;
+                float oldmy = 0;
+                float oldmz = 0;
+
+                while (deadline > DateTime.Now)
+                {
+                    Application.DoEvents();
+
+                    if (oldmx != MainV2.cs.mx &&
+                        oldmy != MainV2.cs.my &&
+                        oldmz != MainV2.cs.mz)
+                    {
+                        data.Add(new Tuple<float, float, float>(
+                            MainV2.cs.mx - (float)MainV2.cs.mag_ofs_x,
+                            MainV2.cs.my - (float)MainV2.cs.mag_ofs_y,
+                            MainV2.cs.mz - (float)MainV2.cs.mag_ofs_z));
+
+                        oldmx = MainV2.cs.mx;
+                        oldmy = MainV2.cs.my;
+                        oldmz = MainV2.cs.mz;
+                    }
+                }
+
+                MainV2.cs.ratesensors = backupratesens;
+
+                if (data.Count < 10)
+                {
+                    CustomMessageBox.Show("Log does not contain enough data");
+                    return;
+                }
+
+                double[] ans = MagCalib.LeastSq(data);
+
+                MagCalib.SaveOffsets(ans);
+
+            }
+            else
+            {
+                string minthro = "30";
+                Common.InputBox("Min Throttle", "Use only data above this throttle percent.", ref minthro);
+
+                int ans = 0;
+                int.TryParse(minthro, out ans);
+
+                MagCalib.ProcessLog(ans);
+            }
+        }
+
+        private void linkLabel1_LinkClicked(object sender, LinkLabelLinkClickedEventArgs e)
+        {
+            try
+            {
+                //System.Diagnostics.Process.Start("http://www.ngdc.noaa.gov/geomagmodels/Declination.jsp");
+                System.Diagnostics.Process.Start("http://www.magnetic-declination.com/");
+            }
+            catch { CustomMessageBox.Show("Webpage open failed... do you have a virus?\nhttp://www.magnetic-declination.com/"); }
+        }
+
+        private void TXT_declination_Validating(object sender, CancelEventArgs e)
+        {
+            float ans = 0;
+            e.Cancel = !float.TryParse(TXT_declination.Text, out ans);
+        }
+
+        private void TXT_declination_Validated(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            try
+            {
+                if (MainV2.comPort.param["COMPASS_DEC"] == null)
+                {
+                    CustomMessageBox.Show("Not Available");
+                }
+                else
+                {
+                    float dec = 0.0f;
+                    try
+                    {
+                        string declination = TXT_declination.Text;
+                        float.TryParse(declination, out dec);
+                        float deg = (float)((int)dec);
+                        float mins = (dec - deg);
+                        if (dec > 0)
+                        {
+                            dec += ((mins) / 60.0f);
+                        }
+                        else
+                        {
+                            dec -= ((mins) / 60.0f);
+                        }
+                    }
+                    catch { CustomMessageBox.Show("Invalid input!"); return; }
+
+                    TXT_declination.Text = dec.ToString();
+
+                    MainV2.comPort.setParam("COMPASS_DEC", dec * deg2rad);
+                }
+            }
+            catch { CustomMessageBox.Show("Set COMPASS_DEC Failed"); }
+        }
+
+
+        private void CHK_enablecompass_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            try
+            {
+                if (MainV2.comPort.param["MAG_ENABLE"] == null)
+                {
+                    CustomMessageBox.Show("Not Available");
+                }
+                else
+                {
+                    MainV2.comPort.setParam("MAG_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
+                }
+            }
+            catch { CustomMessageBox.Show("Set MAG_ENABLE Failed"); }
+        }
+
+        private void CHK_enablesonar_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            try
+            {
+                if (MainV2.comPort.param["SONAR_ENABLE"] == null)
+                {
+                    CustomMessageBox.Show("Not Available");
+                }
+                else
+                {
+                    MainV2.comPort.setParam("SONAR_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
+                }
+            }
+            catch { CustomMessageBox.Show("Set SONAR_ENABLE Failed"); }
+        }
+
+        private void CHK_enableairspeed_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            try
+            {
+                if (MainV2.comPort.param["ARSPD_ENABLE"] == null)
+                {
+                    CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+                }
+                else
+                {
+                    MainV2.comPort.setParam("ARSPD_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
+                }
+            }
+            catch { CustomMessageBox.Show("Set ARSPD_ENABLE Failed"); }
+        }
+
+        private void CHK_enableoptflow_CheckedChanged(object sender, EventArgs e)
+        {
+
+            if (startup)
+                return;
+            try
+            {
+                if (MainV2.comPort.param["FLOW_ENABLE"] == null)
+                {
+                    CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+                }
+                else
+                {
+                    MainV2.comPort.setParam("FLOW_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
+                }
+            }
+            catch { CustomMessageBox.Show("Set FLOW_ENABLE Failed"); }
+        }
+
+        private void CMB_sonartype_SelectedIndexChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            try
+            {
+                if (MainV2.comPort.param["SONAR_TYPE"] == null)
+                {
+                    CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+                }
+                else
+                {
+                    MainV2.comPort.setParam("SONAR_TYPE", ((ComboBox)sender).SelectedIndex);
+                }
+            }
+            catch { CustomMessageBox.Show("Set SONAR_TYPE Failed"); }
+        }
+
+        private void ConfigHardwareOptions_Load(object sender, EventArgs e)
+        {
+            if (!MainV2.comPort.BaseStream.IsOpen)
+            {
+                this.Enabled = false;
+                return;
+            }
+            else
+            {
+                this.Enabled = true;
+            }
+
+            startup = true;
+
+            if (MainV2.comPort.param["ARSPD_ENABLE"] != null)
+                CHK_enableairspeed.Checked = MainV2.comPort.param["ARSPD_ENABLE"].ToString() == "1" ? true : false;
+
+            if (MainV2.comPort.param["SONAR_ENABLE"] != null)
+                CHK_enablesonar.Checked = MainV2.comPort.param["SONAR_ENABLE"].ToString() == "1" ? true : false;
+
+            if (MainV2.comPort.param["MAG_ENABLE"] != null)
+                CHK_enablecompass.Checked = MainV2.comPort.param["MAG_ENABLE"].ToString() == "1" ? true : false;
+
+            if (MainV2.comPort.param["COMPASS_DEC"] != null)
+                TXT_declination.Text = (float.Parse(MainV2.comPort.param["COMPASS_DEC"].ToString()) * rad2deg).ToString();
+
+            if (MainV2.comPort.param["SONAR_TYPE"] != null)
+                CMB_sonartype.SelectedIndex = int.Parse(MainV2.comPort.param["SONAR_TYPE"].ToString());
+
+            if (MainV2.comPort.param["FLOW_ENABLE"] != null)
+                CHK_enableoptflow.Checked = MainV2.comPort.param["FLOW_ENABLE"].ToString() == "1" ? true : false;
+
+
+            startup = false;
+        }
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.es-ES.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.es-ES.resx
new file mode 100644
index 0000000000000000000000000000000000000000..70ad73f1af84a8cec236442b9c51462353fceab5
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.es-ES.resx
@@ -0,0 +1,315 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manual</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Modo actual:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Habilitar el flujo óptico</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>NOTA: Las imágenes son sólo para su presentación</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Actual:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APMSetup</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Swash-Servo posición</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Activar Compas</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Ajuste Chásis (+ or x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modos</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Reset</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Superior</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Swash de Viaje</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manual</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Timón de Viaje</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibración del sensor de voltaje:Para calibrar el sensor, use un multímetro para medir la tensión que sale de la CES de la batería-la eliminación del circuito (se trata de cables negro y rojo en el cable de tres hilos que suministra energía a la placa APM).Luego reste 0,3 V de ese valor y entrar en él en el campo # 1 a la izquierda.</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrar Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Modo de Vuelo 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Alabeo Max</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Modo de Vuelo 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Cabeceo Max</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>por ejemplo, en grados 2 ° 3 'W es -2,3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Modo de Vuelo 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Nivel tu quad para establecer las compensaciones por defecto acel</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Modo de Vuelo 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacidad</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Declinación</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Activar Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Entrada Radio</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibración</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Modo de Vuelo 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Modo de Vuelo 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Gyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Sitio Web Declinación</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batería</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Cero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Activar Airspeed</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Restablecer los Ajustes de hardware APM</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.fr.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.fr.resx
new file mode 100644
index 0000000000000000000000000000000000000000..1bd274beea2e052315a0ab1e83d3619dcf47cbf1
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.fr.resx
@@ -0,0 +1,312 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manuel</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Mode Courant:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Activ. capteur optique</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>NOTE: images pou presentation uniquement. Fonctionnel pour Hex, Octo etc...</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Actuel:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APMSetup</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Swash-Servo position</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Activ. Boussole</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>type de châssis (+ ou x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modes</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Réinit.</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Haut</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Mouvement Swash</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manuel</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Deplac. du Gouvernail</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibration du capteur de Voltage.1. Mesurer le voltage sur APM et inscrivez-le dans la boite ci-bas.2. Mesurer le voltage de la batterie et inscrivez-le dans la boite ci-bas.3. Inscrire les ampères par volt de la documentation du capteur de courant ci-bas</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrer Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Mode de vol 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Roulis Max</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Mode de vol 2</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Tangage Max</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>en degrés eg 2° 3' W est -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Mode de vol 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Niveler l'apareil pour copensation des accels</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Mode de vol 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacité</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Déclination</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Activer Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Entrée Radio</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Mode de vol 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Mode de vol 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Gyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Matériel</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Site Web Déclination</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batterie</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zéro</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Activ. Airspeed</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>RàZ tout parametres du APM</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Moniteur</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.it-IT.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.it-IT.resx
new file mode 100644
index 0000000000000000000000000000000000000000..2b2636c8132c76e5855c9dbb2c87151786f287c3
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.it-IT.resx
@@ -0,0 +1,318 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manuale</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Modo Corrente:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Abilita Flusso ottico</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>Nota: le immagini sono sono per presentazione, funzionerà con Hexa, etc.</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevatore CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Corrente:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>Imposta APM</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Posizione del servo del piatto</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Abilita Magnetometro</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Imposta Frame (+ or x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modi</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Riavvia</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Alto</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Escursione del piatto</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manuale</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Escursione Timone</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibarzione del sensore di voltaggio:
+1. Misura il valtaggio di ingresso di APM e inseriscilo nel box sotto 
+2. Misura il voltaggio della batteria e inseriscilo nel box sotto 
+3. Dalle caratteristiche del sensore di corrente, inserisci il valore degli ampere per volt nel box qui sotto</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrazione Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Massimo</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Modo di volo 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Rollio massimo</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Modo di volo 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Passo massimo</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>in gradi es 2° 3' W is -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Modo di volo 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Livella il quad per impostare gli accelerometri</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Modo di volo 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacità</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Declinazione</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Attiva Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Ingresso Radio</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibration</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Modo di volo 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Modo di volo 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Giroscopio</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Sito Web per la Declinazione</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batteria</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Attiva Sensore Velocità</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Resetta APM ai valori di Default</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.pl.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.pl.resx
new file mode 100644
index 0000000000000000000000000000000000000000..057b9327168c6471be22139b5d017e20582de843
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.pl.resx
@@ -0,0 +1,318 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Ręczne</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Aktualny tryb:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Włącz Optical Flow</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>UWAGA: Obrazy są wyłącznie do prezentacji, działają jedynie z hexa, itp.</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Odwr. Elevon CH1</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>Aktualny PWM:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>Ustawienia APM</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Pozycja serwa płyty ster.</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Włącz kompas</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Ustawienie ramy (+ lub x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Tryby</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Reset</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Góra</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Zakres ruchu płyty sterującej</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Ręczne</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Zakres steru kierunku</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Kalibracja czujnika napięcia:
+1. Zmierz napięcie wejściowe APM i wpisz poniżej
+2. Zmierz napięcie baterii i wpisz poniżej
+3. Wpisz poniżej ilość amperów/wolt [A/V] z dokumentacji czujnika prądu</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Kalibracja radia</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Tryb lotu 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Max przechylenie</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Tryb lotu 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Max pochylenie</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>w stopniech np. 2° 3' W to -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Tryb lotu 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Wypoziomuj quada żeby stawić domyśle offsety przysp.</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Tryb lotu 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Pojemność</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Deklinacja</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Włącz sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Wejścia radia</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibration</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Tryb lotu 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Tryb lotu 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Żyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Strona www deklinacji</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Bateria</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Włącz prędkość powietrza</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Reset APM do stawień domyślnych</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx
new file mode 100644
index 0000000000000000000000000000000000000000..587576ac954865411038feb5d6e72275baa582e9
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx
@@ -0,0 +1,522 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
+  <data name="BUT_MagCalibration.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="BUT_MagCalibration.Location" type="System.Drawing.Point, System.Drawing">
+    <value>340, 13</value>
+  </data>
+  <data name="BUT_MagCalibration.Size" type="System.Drawing.Size, System.Drawing">
+    <value>75, 23</value>
+  </data>
+  <assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
+  <data name="BUT_MagCalibration.TabIndex" type="System.Int32, mscorlib">
+    <value>47</value>
+  </data>
+  <data name="BUT_MagCalibration.Text" xml:space="preserve">
+    <value>Calibration</value>
+  </data>
+  <data name="&gt;&gt;BUT_MagCalibration.Name" xml:space="preserve">
+    <value>BUT_MagCalibration</value>
+  </data>
+  <data name="&gt;&gt;BUT_MagCalibration.Type" xml:space="preserve">
+    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;BUT_MagCalibration.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;BUT_MagCalibration.ZOrder" xml:space="preserve">
+    <value>0</value>
+  </data>
+  <data name="label27.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label27.Location" type="System.Drawing.Point, System.Drawing">
+    <value>445, 45</value>
+  </data>
+  <data name="label27.Size" type="System.Drawing.Size, System.Drawing">
+    <value>150, 20</value>
+  </data>
+  <data name="label27.TabIndex" type="System.Int32, mscorlib">
+    <value>46</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>in Degrees eg 2° 3' W is -2.3</value>
+  </data>
+  <data name="&gt;&gt;label27.Name" xml:space="preserve">
+    <value>label27</value>
+  </data>
+  <data name="&gt;&gt;label27.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label27.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label27.ZOrder" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CMB_sonartype.Items" xml:space="preserve">
+    <value>XL-EZ0</value>
+  </data>
+  <data name="CMB_sonartype.Items1" xml:space="preserve">
+    <value>LV-EZ0</value>
+  </data>
+  <data name="CMB_sonartype.Items2" xml:space="preserve">
+    <value>XL-EZL0</value>
+  </data>
+  <data name="CMB_sonartype.Location" type="System.Drawing.Point, System.Drawing">
+    <value>243, 122</value>
+  </data>
+  <data name="CMB_sonartype.Size" type="System.Drawing.Size, System.Drawing">
+    <value>121, 21</value>
+  </data>
+  <data name="CMB_sonartype.TabIndex" type="System.Int32, mscorlib">
+    <value>45</value>
+  </data>
+  <data name="&gt;&gt;CMB_sonartype.Name" xml:space="preserve">
+    <value>CMB_sonartype</value>
+  </data>
+  <data name="&gt;&gt;CMB_sonartype.Type" xml:space="preserve">
+    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CMB_sonartype.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CMB_sonartype.ZOrder" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="CHK_enableoptflow.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="CHK_enableoptflow.Location" type="System.Drawing.Point, System.Drawing">
+    <value>97, 285</value>
+  </data>
+  <data name="CHK_enableoptflow.Size" type="System.Drawing.Size, System.Drawing">
+    <value>134, 19</value>
+  </data>
+  <data name="CHK_enableoptflow.TabIndex" type="System.Int32, mscorlib">
+    <value>44</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Enable Optical Flow</value>
+  </data>
+  <data name="&gt;&gt;CHK_enableoptflow.Name" xml:space="preserve">
+    <value>CHK_enableoptflow</value>
+  </data>
+  <data name="&gt;&gt;CHK_enableoptflow.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CHK_enableoptflow.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CHK_enableoptflow.ZOrder" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="pictureBox2.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
+    <value>Zoom</value>
+  </data>
+  <data name="pictureBox2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="pictureBox2.Location" type="System.Drawing.Point, System.Drawing">
+    <value>13, 259</value>
+  </data>
+  <data name="pictureBox2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>75, 75</value>
+  </data>
+  <data name="pictureBox2.TabIndex" type="System.Int32, mscorlib">
+    <value>43</value>
+  </data>
+  <data name="&gt;&gt;pictureBox2.Name" xml:space="preserve">
+    <value>pictureBox2</value>
+  </data>
+  <data name="&gt;&gt;pictureBox2.Type" xml:space="preserve">
+    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;pictureBox2.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;pictureBox2.ZOrder" xml:space="preserve">
+    <value>4</value>
+  </data>
+  <data name="linkLabelmagdec.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="linkLabelmagdec.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="linkLabelmagdec.Location" type="System.Drawing.Point, System.Drawing">
+    <value>325, 68</value>
+  </data>
+  <data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
+    <value>104, 13</value>
+  </data>
+  <data name="linkLabelmagdec.TabIndex" type="System.Int32, mscorlib">
+    <value>42</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Declination WebSite</value>
+  </data>
+  <data name="&gt;&gt;linkLabelmagdec.Name" xml:space="preserve">
+    <value>linkLabelmagdec</value>
+  </data>
+  <data name="&gt;&gt;linkLabelmagdec.Type" xml:space="preserve">
+    <value>System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;linkLabelmagdec.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;linkLabelmagdec.ZOrder" xml:space="preserve">
+    <value>5</value>
+  </data>
+  <data name="label100.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label100.Location" type="System.Drawing.Point, System.Drawing">
+    <value>240, 45</value>
+  </data>
+  <data name="label100.Size" type="System.Drawing.Size, System.Drawing">
+    <value>72, 16</value>
+  </data>
+  <data name="label100.TabIndex" type="System.Int32, mscorlib">
+    <value>38</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Declination</value>
+  </data>
+  <data name="&gt;&gt;label100.Name" xml:space="preserve">
+    <value>label100</value>
+  </data>
+  <data name="&gt;&gt;label100.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label100.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label100.ZOrder" xml:space="preserve">
+    <value>6</value>
+  </data>
+  <data name="TXT_declination.Location" type="System.Drawing.Point, System.Drawing">
+    <value>318, 45</value>
+  </data>
+  <data name="TXT_declination.Size" type="System.Drawing.Size, System.Drawing">
+    <value>121, 20</value>
+  </data>
+  <data name="TXT_declination.TabIndex" type="System.Int32, mscorlib">
+    <value>37</value>
+  </data>
+  <data name="&gt;&gt;TXT_declination.Name" xml:space="preserve">
+    <value>TXT_declination</value>
+  </data>
+  <data name="&gt;&gt;TXT_declination.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;TXT_declination.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;TXT_declination.ZOrder" xml:space="preserve">
+    <value>7</value>
+  </data>
+  <data name="CHK_enableairspeed.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="CHK_enableairspeed.Location" type="System.Drawing.Point, System.Drawing">
+    <value>97, 202</value>
+  </data>
+  <data name="CHK_enableairspeed.Size" type="System.Drawing.Size, System.Drawing">
+    <value>103, 17</value>
+  </data>
+  <data name="CHK_enableairspeed.TabIndex" type="System.Int32, mscorlib">
+    <value>39</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Enable Airspeed</value>
+  </data>
+  <data name="&gt;&gt;CHK_enableairspeed.Name" xml:space="preserve">
+    <value>CHK_enableairspeed</value>
+  </data>
+  <data name="&gt;&gt;CHK_enableairspeed.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CHK_enableairspeed.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CHK_enableairspeed.ZOrder" xml:space="preserve">
+    <value>8</value>
+  </data>
+  <data name="CHK_enablesonar.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="CHK_enablesonar.Location" type="System.Drawing.Point, System.Drawing">
+    <value>94, 124</value>
+  </data>
+  <data name="CHK_enablesonar.Size" type="System.Drawing.Size, System.Drawing">
+    <value>90, 17</value>
+  </data>
+  <data name="CHK_enablesonar.TabIndex" type="System.Int32, mscorlib">
+    <value>40</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Enable Sonar</value>
+  </data>
+  <data name="&gt;&gt;CHK_enablesonar.Name" xml:space="preserve">
+    <value>CHK_enablesonar</value>
+  </data>
+  <data name="&gt;&gt;CHK_enablesonar.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CHK_enablesonar.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CHK_enablesonar.ZOrder" xml:space="preserve">
+    <value>9</value>
+  </data>
+  <data name="CHK_enablecompass.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="CHK_enablecompass.Location" type="System.Drawing.Point, System.Drawing">
+    <value>97, 44</value>
+  </data>
+  <data name="CHK_enablecompass.Size" type="System.Drawing.Size, System.Drawing">
+    <value>105, 17</value>
+  </data>
+  <data name="CHK_enablecompass.TabIndex" type="System.Int32, mscorlib">
+    <value>41</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Enable Compass</value>
+  </data>
+  <data name="&gt;&gt;CHK_enablecompass.Name" xml:space="preserve">
+    <value>CHK_enablecompass</value>
+  </data>
+  <data name="&gt;&gt;CHK_enablecompass.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CHK_enablecompass.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CHK_enablecompass.ZOrder" xml:space="preserve">
+    <value>10</value>
+  </data>
+  <data name="pictureBox4.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
+    <value>Zoom</value>
+  </data>
+  <data name="pictureBox4.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="pictureBox4.Location" type="System.Drawing.Point, System.Drawing">
+    <value>13, 176</value>
+  </data>
+  <data name="pictureBox4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>75, 75</value>
+  </data>
+  <data name="pictureBox4.TabIndex" type="System.Int32, mscorlib">
+    <value>36</value>
+  </data>
+  <data name="&gt;&gt;pictureBox4.Name" xml:space="preserve">
+    <value>pictureBox4</value>
+  </data>
+  <data name="&gt;&gt;pictureBox4.Type" xml:space="preserve">
+    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;pictureBox4.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;pictureBox4.ZOrder" xml:space="preserve">
+    <value>11</value>
+  </data>
+  <data name="pictureBox3.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
+    <value>Zoom</value>
+  </data>
+  <data name="pictureBox3.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="pictureBox3.Location" type="System.Drawing.Point, System.Drawing">
+    <value>13, 94</value>
+  </data>
+  <data name="pictureBox3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>75, 75</value>
+  </data>
+  <data name="pictureBox3.TabIndex" type="System.Int32, mscorlib">
+    <value>35</value>
+  </data>
+  <data name="&gt;&gt;pictureBox3.Name" xml:space="preserve">
+    <value>pictureBox3</value>
+  </data>
+  <data name="&gt;&gt;pictureBox3.Type" xml:space="preserve">
+    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;pictureBox3.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;pictureBox3.ZOrder" xml:space="preserve">
+    <value>12</value>
+  </data>
+  <data name="pictureBox1.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
+    <value>Zoom</value>
+  </data>
+  <data name="pictureBox1.ErrorImage" type="System.Resources.ResXNullRef, System.Windows.Forms">
+    <value />
+  </data>
+  <data name="pictureBox1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="pictureBox1.InitialImage" type="System.Resources.ResXNullRef, System.Windows.Forms">
+    <value />
+  </data>
+  <data name="pictureBox1.Location" type="System.Drawing.Point, System.Drawing">
+    <value>13, 13</value>
+  </data>
+  <data name="pictureBox1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>75, 75</value>
+  </data>
+  <data name="pictureBox1.TabIndex" type="System.Int32, mscorlib">
+    <value>34</value>
+  </data>
+  <data name="&gt;&gt;pictureBox1.Name" xml:space="preserve">
+    <value>pictureBox1</value>
+  </data>
+  <data name="&gt;&gt;pictureBox1.Type" xml:space="preserve">
+    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;pictureBox1.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;pictureBox1.ZOrder" xml:space="preserve">
+    <value>13</value>
+  </data>
+  <metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
+    <value>True</value>
+  </metadata>
+  <data name="$this.AutoScaleDimensions" type="System.Drawing.SizeF, System.Drawing">
+    <value>6, 13</value>
+  </data>
+  <data name="$this.Size" type="System.Drawing.Size, System.Drawing">
+    <value>602, 351</value>
+  </data>
+  <data name="&gt;&gt;$this.Name" xml:space="preserve">
+    <value>ConfigHardwareOptions</value>
+  </data>
+  <data name="&gt;&gt;$this.Type" xml:space="preserve">
+    <value>System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.zh-Hans.resx
new file mode 100644
index 0000000000000000000000000000000000000000..f96892c423b112b28127ad582686f33464b57c5b
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.zh-Hans.resx
@@ -0,0 +1,496 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>遥控输入</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>模式</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>硬件</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>电池</value>
+  </data>
+  <data name="tabHeli.Text" xml:space="preserve">
+    <value>AC2 直升机</value>
+  </data>
+  <data name="groupBoxElevons.Text" xml:space="preserve">
+    <value>上降副翼 (Elevon) 配置</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="CHK_elevonch2rev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>115, 17</value>
+  </data>
+  <data name="CHK_elevonch2rev.Text" xml:space="preserve">
+    <value>Elevons CH2 逆转</value>
+  </data>
+  <data name="CHK_elevonrev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>91, 17</value>
+  </data>
+  <data name="CHK_elevonrev.Text" xml:space="preserve">
+    <value>Elevons 逆转</value>
+  </data>
+  <data name="CHK_elevonch1rev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>115, 17</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 逆转</value>
+  </data>
+  <data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch3.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch4.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch2.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch1.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>校准遥控</value>
+  </data>
+  <data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="label14.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>当前 PWM:</value>
+  </data>
+  <data name="label13.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>当前模式:</value>
+  </data>
+  <data name="label6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>飞行模式 6</value>
+  </data>
+  <data name="label5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>飞行模式 5</value>
+  </data>
+  <data name="label4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>飞行模式 4</value>
+  </data>
+  <data name="label3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>飞行模式 3</value>
+  </data>
+  <data name="label2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>飞行模式 2</value>
+  </data>
+  <data name="label1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>飞行模式 1</value>
+  </data>
+  <data name="BUT_SaveModes.Text" xml:space="preserve">
+    <value>保存模式</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>十进制, 2° 3' W 就是 -2.3</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>启用光流</value>
+  </data>
+  <data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
+    <value>67, 13</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>磁偏角网站</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>磁偏角</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>启用空速计</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>启用声纳</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>启用罗盘</value>
+  </data>
+  <data name="label31.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label31.Text" xml:space="preserve">
+    <value>输入电压:</value>
+  </data>
+  <data name="label32.Size" type="System.Drawing.Size, System.Drawing">
+    <value>94, 13</value>
+  </data>
+  <data name="label32.Text" xml:space="preserve">
+    <value>测量的电池电压:</value>
+  </data>
+  <data name="label33.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label33.Text" xml:space="preserve">
+    <value>电池电压:</value>
+  </data>
+  <data name="label34.Size" type="System.Drawing.Size, System.Drawing">
+    <value>52, 13</value>
+  </data>
+  <data name="label34.Text" xml:space="preserve">
+    <value>分 压 比:</value>
+  </data>
+  <data name="label35.Size" type="System.Drawing.Size, System.Drawing">
+    <value>63, 13</value>
+  </data>
+  <data name="label35.Text" xml:space="preserve">
+    <value>安培/伏特:</value>
+  </data>
+  <data name="label47.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 18</value>
+  </data>
+  <data name="label47.Text" xml:space="preserve">
+    <value>传感器</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>电压传感器校准:
+1. 测量APM输入电压,输入到下方的文本框中
+2. 测量电池电压,输入到下方的文本框中
+3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中</value>
+  </data>
+  <data name="label29.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>容量</value>
+  </data>
+  <data name="label30.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 13</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>监控器</value>
+  </data>
+  <data name="label28.Size" type="System.Drawing.Size, System.Drawing">
+    <value>175, 13</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>设置水平面的默认加速度计偏移</value>
+  </data>
+  <data name="label16.Size" type="System.Drawing.Size, System.Drawing">
+    <value>261, 13</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>注: 图片只是用于展示,设置可以用于六轴等机架</value>
+  </data>
+  <data name="label15.Size" type="System.Drawing.Size, System.Drawing">
+    <value>93, 13</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>机架设置 (+ 或 x)</value>
+  </data>
+  <data name="BUT_levelac2.Text" xml:space="preserve">
+    <value>找平</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>手动</value>
+  </data>
+  <data name="BUT_swash_manual.Text" xml:space="preserve">
+    <value>手动</value>
+  </data>
+  <data name="label46.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label46.Text" xml:space="preserve">
+    <value>感度</value>
+  </data>
+  <data name="label45.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label45.Text" xml:space="preserve">
+    <value>启用</value>
+  </data>
+  <data name="label44.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label44.Text" xml:space="preserve">
+    <value>微调</value>
+  </data>
+  <data name="label43.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label43.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="label42.Size" type="System.Drawing.Size, System.Drawing">
+    <value>43, 13</value>
+  </data>
+  <data name="label42.Text" xml:space="preserve">
+    <value>方向舵</value>
+  </data>
+  <data name="label24.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>最大</value>
+  </data>
+  <data name="label40.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label40.Text" xml:space="preserve">
+    <value>最小</value>
+  </data>
+  <data name="label41.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label41.Text" xml:space="preserve">
+    <value>最低</value>
+  </data>
+  <data name="label21.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>最高</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>0度</value>
+  </data>
+  <data name="label39.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label39.Text" xml:space="preserve">
+    <value>微调</value>
+  </data>
+  <data name="label38.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label38.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="label37.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label37.Text" xml:space="preserve">
+    <value>位置</value>
+  </data>
+  <data name="label36.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label36.Text" xml:space="preserve">
+    <value>舵机</value>
+  </data>
+  <data name="label26.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>最大俯仰</value>
+  </data>
+  <data name="label25.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>最大侧倾</value>
+  </data>
+  <data name="label23.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>舵机行程</value>
+  </data>
+  <data name="label22.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>斜盘水平微调</value>
+  </data>
+  <data name="label17.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>斜盘舵机位置</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>重置</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>重置 APM 为默认设置</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APM设置</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.zh-TW.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.zh-TW.resx
new file mode 100644
index 0000000000000000000000000000000000000000..0c03fbf8ed6bd5befc34246175bf1adf106cce43
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.zh-TW.resx
@@ -0,0 +1,460 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>重置</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>遙控輸入</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>模式</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>硬件</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>電池</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>重置 APM 為默認設置</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch3.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch4.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch2.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch1.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>校準遙控</value>
+  </data>
+  <data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="label14.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>當前 PWM:</value>
+  </data>
+  <data name="label13.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>當前模式:</value>
+  </data>
+  <data name="label6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>飛行模式 6</value>
+  </data>
+  <data name="label5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>飛行模式 5</value>
+  </data>
+  <data name="label4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>飛行模式 4</value>
+  </data>
+  <data name="label3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>飛行模式 3</value>
+  </data>
+  <data name="label2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>飛行模式 2</value>
+  </data>
+  <data name="label1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>飛行模式 1</value>
+  </data>
+  <data name="BUT_SaveModes.Text" xml:space="preserve">
+    <value>保存模式</value>
+  </data>
+  <data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
+    <value>67, 13</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>磁偏角網站</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>磁偏角</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>啟用空速計</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>啟用聲納</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>啟用羅盤</value>
+  </data>
+  <data name="label35.Size" type="System.Drawing.Size, System.Drawing">
+    <value>63, 13</value>
+  </data>
+  <data name="label35.Text" xml:space="preserve">
+    <value>安培/伏特:</value>
+  </data>
+  <data name="label34.Size" type="System.Drawing.Size, System.Drawing">
+    <value>52, 13</value>
+  </data>
+  <data name="label34.Text" xml:space="preserve">
+    <value>分 壓 比:</value>
+  </data>
+  <data name="label33.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label33.Text" xml:space="preserve">
+    <value>電池電壓:</value>
+  </data>
+  <data name="label32.Size" type="System.Drawing.Size, System.Drawing">
+    <value>94, 13</value>
+  </data>
+  <data name="label32.Text" xml:space="preserve">
+    <value>測量的電池電壓:</value>
+  </data>
+  <data name="label31.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label31.Text" xml:space="preserve">
+    <value>輸入電壓:</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>電壓傳感器校準:
+1. 測量APM輸入電壓,輸入到下方的文本框中
+2. 測量電池電壓,輸入到下方的文本框中
+3. 從當前的傳感器的數據表中找到安培/伏特,輸入到下方的文本框中</value>
+  </data>
+  <data name="label29.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>容量</value>
+  </data>
+  <data name="label30.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 13</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>監控器</value>
+  </data>
+  <data name="label28.Size" type="System.Drawing.Size, System.Drawing">
+    <value>175, 13</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>設置水平面的默認加速度計偏移</value>
+  </data>
+  <data name="label16.Size" type="System.Drawing.Size, System.Drawing">
+    <value>261, 13</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>注: 圖片只是用於展示,設置可以用於六軸等機架</value>
+  </data>
+  <data name="label15.Size" type="System.Drawing.Size, System.Drawing">
+    <value>93, 13</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>機架設置 (+ 或 x)</value>
+  </data>
+  <data name="BUT_levelac2.Text" xml:space="preserve">
+    <value>找平</value>
+  </data>
+  <data name="label46.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label46.Text" xml:space="preserve">
+    <value>感度</value>
+  </data>
+  <data name="label45.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label45.Text" xml:space="preserve">
+    <value>啟用</value>
+  </data>
+  <data name="label44.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label44.Text" xml:space="preserve">
+    <value>微調</value>
+  </data>
+  <data name="label43.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label43.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="label42.Size" type="System.Drawing.Size, System.Drawing">
+    <value>43, 13</value>
+  </data>
+  <data name="label42.Text" xml:space="preserve">
+    <value>方向舵</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>手動</value>
+  </data>
+  <data name="label24.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>最大</value>
+  </data>
+  <data name="label40.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label40.Text" xml:space="preserve">
+    <value>最小</value>
+  </data>
+  <data name="BUT_swash_manual.Text" xml:space="preserve">
+    <value>手動</value>
+  </data>
+  <data name="label41.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label41.Text" xml:space="preserve">
+    <value>最低</value>
+  </data>
+  <data name="label21.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>最高</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>0度</value>
+  </data>
+  <data name="label39.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label39.Text" xml:space="preserve">
+    <value>微調</value>
+  </data>
+  <data name="label38.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label38.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="label37.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label37.Text" xml:space="preserve">
+    <value>位置</value>
+  </data>
+  <data name="label36.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label36.Text" xml:space="preserve">
+    <value>舵機</value>
+  </data>
+  <data name="label26.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>最大俯仰</value>
+  </data>
+  <data name="label25.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>最大側傾</value>
+  </data>
+  <data name="label23.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>舵機行程</value>
+  </data>
+  <data name="label22.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>斜盤水平微調</value>
+  </data>
+  <data name="label17.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>斜盤舵機位置</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APM設置</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs
new file mode 100644
index 0000000000000000000000000000000000000000..ec5a15499e240852066363b23f5a4942f9172254
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs
@@ -0,0 +1,677 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    partial class ConfigPlanner
+    {
+        /// <summary> 
+        /// Required designer variable.
+        /// </summary>
+        private System.ComponentModel.IContainer components = null;
+
+        /// <summary> 
+        /// Clean up any resources being used.
+        /// </summary>
+        /// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
+        protected override void Dispose(bool disposing)
+        {
+            if (disposing && (components != null))
+            {
+                components.Dispose();
+            }
+            base.Dispose(disposing);
+        }
+
+        #region Component Designer generated code
+
+        /// <summary> 
+        /// Required method for Designer support - do not modify 
+        /// the contents of this method with the code editor.
+        /// </summary>
+        private void InitializeComponent()
+        {
+            this.label33 = new System.Windows.Forms.Label();
+            this.CMB_ratesensors = new System.Windows.Forms.ComboBox();
+            this.label26 = new System.Windows.Forms.Label();
+            this.CMB_videoresolutions = new System.Windows.Forms.ComboBox();
+            this.label12 = new System.Windows.Forms.Label();
+            this.CHK_GDIPlus = new System.Windows.Forms.CheckBox();
+            this.label24 = new System.Windows.Forms.Label();
+            this.CHK_loadwponconnect = new System.Windows.Forms.CheckBox();
+            this.label23 = new System.Windows.Forms.Label();
+            this.NUM_tracklength = new System.Windows.Forms.NumericUpDown();
+            this.CHK_speechaltwarning = new System.Windows.Forms.CheckBox();
+            this.label108 = new System.Windows.Forms.Label();
+            this.CHK_resetapmonconnect = new System.Windows.Forms.CheckBox();
+            this.CHK_mavdebug = new System.Windows.Forms.CheckBox();
+            this.label107 = new System.Windows.Forms.Label();
+            this.CMB_raterc = new System.Windows.Forms.ComboBox();
+            this.label104 = new System.Windows.Forms.Label();
+            this.label103 = new System.Windows.Forms.Label();
+            this.label102 = new System.Windows.Forms.Label();
+            this.label101 = new System.Windows.Forms.Label();
+            this.CMB_ratestatus = new System.Windows.Forms.ComboBox();
+            this.CMB_rateposition = new System.Windows.Forms.ComboBox();
+            this.CMB_rateattitude = new System.Windows.Forms.ComboBox();
+            this.label99 = new System.Windows.Forms.Label();
+            this.label98 = new System.Windows.Forms.Label();
+            this.label97 = new System.Windows.Forms.Label();
+            this.CMB_speedunits = new System.Windows.Forms.ComboBox();
+            this.CMB_distunits = new System.Windows.Forms.ComboBox();
+            this.label96 = new System.Windows.Forms.Label();
+            this.label95 = new System.Windows.Forms.Label();
+            this.CHK_speechbattery = new System.Windows.Forms.CheckBox();
+            this.CHK_speechcustom = new System.Windows.Forms.CheckBox();
+            this.CHK_speechmode = new System.Windows.Forms.CheckBox();
+            this.CHK_speechwaypoint = new System.Windows.Forms.CheckBox();
+            this.label94 = new System.Windows.Forms.Label();
+            this.CMB_osdcolor = new System.Windows.Forms.ComboBox();
+            this.CMB_language = new System.Windows.Forms.ComboBox();
+            this.label93 = new System.Windows.Forms.Label();
+            this.CHK_enablespeech = new System.Windows.Forms.CheckBox();
+            this.CHK_hudshow = new System.Windows.Forms.CheckBox();
+            this.label92 = new System.Windows.Forms.Label();
+            this.CMB_videosources = new System.Windows.Forms.ComboBox();
+            this.BUT_Joystick = new ArdupilotMega.MyButton();
+            this.BUT_videostop = new ArdupilotMega.MyButton();
+            this.BUT_videostart = new ArdupilotMega.MyButton();
+            ((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).BeginInit();
+            this.SuspendLayout();
+            // 
+            // label33
+            // 
+            this.label33.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label33.Location = new System.Drawing.Point(517, 246);
+            this.label33.Name = "label33";
+            this.label33.Size = new System.Drawing.Size(43, 13);
+            this.label33.TabIndex = 87;
+            this.label33.Text = "Sensor";
+            // 
+            // CMB_ratesensors
+            // 
+            this.CMB_ratesensors.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CMB_ratesensors.FormattingEnabled = true;
+            this.CMB_ratesensors.Items.AddRange(new object[] {
+            "0",
+            "1",
+            "3",
+            "10",
+            "50"});
+            this.CMB_ratesensors.Location = new System.Drawing.Point(564, 243);
+            this.CMB_ratesensors.Name = "CMB_ratesensors";
+            this.CMB_ratesensors.Size = new System.Drawing.Size(40, 21);
+            this.CMB_ratesensors.TabIndex = 88;
+            // 
+            // label26
+            // 
+            this.label26.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label26.Location = new System.Drawing.Point(15, 52);
+            this.label26.Name = "label26";
+            this.label26.Size = new System.Drawing.Size(100, 23);
+            this.label26.TabIndex = 86;
+            this.label26.Text = "Video Format";
+            // 
+            // CMB_videoresolutions
+            // 
+            this.CMB_videoresolutions.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CMB_videoresolutions.FormattingEnabled = true;
+            this.CMB_videoresolutions.Location = new System.Drawing.Point(124, 49);
+            this.CMB_videoresolutions.Name = "CMB_videoresolutions";
+            this.CMB_videoresolutions.Size = new System.Drawing.Size(408, 21);
+            this.CMB_videoresolutions.TabIndex = 44;
+            // 
+            // label12
+            // 
+            this.label12.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label12.Location = new System.Drawing.Point(15, 342);
+            this.label12.Name = "label12";
+            this.label12.Size = new System.Drawing.Size(61, 13);
+            this.label12.TabIndex = 84;
+            this.label12.Text = "HUD";
+            // 
+            // CHK_GDIPlus
+            // 
+            this.CHK_GDIPlus.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.CHK_GDIPlus.Location = new System.Drawing.Point(124, 342);
+            this.CHK_GDIPlus.Name = "CHK_GDIPlus";
+            this.CHK_GDIPlus.Size = new System.Drawing.Size(177, 17);
+            this.CHK_GDIPlus.TabIndex = 85;
+            this.CHK_GDIPlus.Text = "GDI+ (old type)";
+            this.CHK_GDIPlus.UseVisualStyleBackColor = true;
+            this.CHK_GDIPlus.CheckedChanged += new System.EventHandler(this.CHK_GDIPlus_CheckedChanged);
+            // 
+            // label24
+            // 
+            this.label24.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label24.Location = new System.Drawing.Point(15, 320);
+            this.label24.Name = "label24";
+            this.label24.Size = new System.Drawing.Size(61, 13);
+            this.label24.TabIndex = 82;
+            this.label24.Text = "Waypoints";
+            // 
+            // CHK_loadwponconnect
+            // 
+            this.CHK_loadwponconnect.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.CHK_loadwponconnect.Location = new System.Drawing.Point(124, 319);
+            this.CHK_loadwponconnect.Name = "CHK_loadwponconnect";
+            this.CHK_loadwponconnect.Size = new System.Drawing.Size(177, 17);
+            this.CHK_loadwponconnect.TabIndex = 83;
+            this.CHK_loadwponconnect.Text = "Load Waypoints on connect?";
+            this.CHK_loadwponconnect.UseVisualStyleBackColor = true;
+            this.CHK_loadwponconnect.CheckedChanged += new System.EventHandler(this.CHK_loadwponconnect_CheckedChanged);
+            // 
+            // label23
+            // 
+            this.label23.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label23.Location = new System.Drawing.Point(15, 294);
+            this.label23.Name = "label23";
+            this.label23.Size = new System.Drawing.Size(103, 18);
+            this.label23.TabIndex = 81;
+            this.label23.Text = "Track Length";
+            // 
+            // NUM_tracklength
+            // 
+            this.NUM_tracklength.Increment = new decimal(new int[] {
+            100,
+            0,
+            0,
+            0});
+            this.NUM_tracklength.Location = new System.Drawing.Point(124, 293);
+            this.NUM_tracklength.Maximum = new decimal(new int[] {
+            2000,
+            0,
+            0,
+            0});
+            this.NUM_tracklength.Minimum = new decimal(new int[] {
+            100,
+            0,
+            0,
+            0});
+            this.NUM_tracklength.Name = "NUM_tracklength";
+            this.NUM_tracklength.Size = new System.Drawing.Size(67, 20);
+            this.NUM_tracklength.TabIndex = 80;
+            this.NUM_tracklength.Value = new decimal(new int[] {
+            200,
+            0,
+            0,
+            0});
+            this.NUM_tracklength.ValueChanged += new System.EventHandler(this.NUM_tracklength_ValueChanged);
+            // 
+            // CHK_speechaltwarning
+            // 
+            this.CHK_speechaltwarning.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.CHK_speechaltwarning.Location = new System.Drawing.Point(564, 109);
+            this.CHK_speechaltwarning.Name = "CHK_speechaltwarning";
+            this.CHK_speechaltwarning.Size = new System.Drawing.Size(102, 17);
+            this.CHK_speechaltwarning.TabIndex = 79;
+            this.CHK_speechaltwarning.Text = "Alt Warning";
+            this.CHK_speechaltwarning.UseVisualStyleBackColor = true;
+            this.CHK_speechaltwarning.CheckedChanged += new System.EventHandler(this.CHK_speechaltwarning_CheckedChanged);
+            // 
+            // label108
+            // 
+            this.label108.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label108.Location = new System.Drawing.Point(15, 271);
+            this.label108.Name = "label108";
+            this.label108.Size = new System.Drawing.Size(61, 13);
+            this.label108.TabIndex = 45;
+            this.label108.Text = "APM Reset";
+            // 
+            // CHK_resetapmonconnect
+            // 
+            this.CHK_resetapmonconnect.Checked = true;
+            this.CHK_resetapmonconnect.CheckState = System.Windows.Forms.CheckState.Checked;
+            this.CHK_resetapmonconnect.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.CHK_resetapmonconnect.Location = new System.Drawing.Point(124, 269);
+            this.CHK_resetapmonconnect.Name = "CHK_resetapmonconnect";
+            this.CHK_resetapmonconnect.Size = new System.Drawing.Size(163, 17);
+            this.CHK_resetapmonconnect.TabIndex = 46;
+            this.CHK_resetapmonconnect.Text = "Reset APM on USB Connect";
+            this.CHK_resetapmonconnect.UseVisualStyleBackColor = true;
+            this.CHK_resetapmonconnect.CheckedChanged += new System.EventHandler(this.CHK_resetapmonconnect_CheckedChanged);
+            // 
+            // CHK_mavdebug
+            // 
+            this.CHK_mavdebug.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Left)));
+            this.CHK_mavdebug.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.CHK_mavdebug.Location = new System.Drawing.Point(15, 378);
+            this.CHK_mavdebug.Name = "CHK_mavdebug";
+            this.CHK_mavdebug.Size = new System.Drawing.Size(144, 17);
+            this.CHK_mavdebug.TabIndex = 47;
+            this.CHK_mavdebug.Text = "Mavlink Message Debug";
+            this.CHK_mavdebug.UseVisualStyleBackColor = true;
+            this.CHK_mavdebug.CheckedChanged += new System.EventHandler(this.CHK_mavdebug_CheckedChanged);
+            // 
+            // label107
+            // 
+            this.label107.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label107.Location = new System.Drawing.Point(439, 246);
+            this.label107.Name = "label107";
+            this.label107.Size = new System.Drawing.Size(22, 13);
+            this.label107.TabIndex = 48;
+            this.label107.Text = "RC";
+            // 
+            // CMB_raterc
+            // 
+            this.CMB_raterc.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CMB_raterc.FormattingEnabled = true;
+            this.CMB_raterc.Items.AddRange(new object[] {
+            "0",
+            "1",
+            "3",
+            "10"});
+            this.CMB_raterc.Location = new System.Drawing.Point(470, 242);
+            this.CMB_raterc.Name = "CMB_raterc";
+            this.CMB_raterc.Size = new System.Drawing.Size(40, 21);
+            this.CMB_raterc.TabIndex = 49;
+            this.CMB_raterc.SelectedIndexChanged += new System.EventHandler(this.CMB_raterc_SelectedIndexChanged);
+            // 
+            // label104
+            // 
+            this.label104.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label104.Location = new System.Drawing.Point(319, 246);
+            this.label104.Name = "label104";
+            this.label104.Size = new System.Drawing.Size(69, 13);
+            this.label104.TabIndex = 50;
+            this.label104.Text = "Mode/Status";
+            // 
+            // label103
+            // 
+            this.label103.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label103.Location = new System.Drawing.Point(219, 246);
+            this.label103.Name = "label103";
+            this.label103.Size = new System.Drawing.Size(44, 13);
+            this.label103.TabIndex = 51;
+            this.label103.Text = "Position";
+            // 
+            // label102
+            // 
+            this.label102.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label102.Location = new System.Drawing.Point(121, 246);
+            this.label102.Name = "label102";
+            this.label102.Size = new System.Drawing.Size(43, 13);
+            this.label102.TabIndex = 52;
+            this.label102.Text = "Attitude";
+            // 
+            // label101
+            // 
+            this.label101.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label101.Location = new System.Drawing.Point(12, 246);
+            this.label101.Name = "label101";
+            this.label101.Size = new System.Drawing.Size(84, 13);
+            this.label101.TabIndex = 53;
+            this.label101.Text = "Telemetry Rates";
+            // 
+            // CMB_ratestatus
+            // 
+            this.CMB_ratestatus.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CMB_ratestatus.FormattingEnabled = true;
+            this.CMB_ratestatus.Items.AddRange(new object[] {
+            "0",
+            "1",
+            "3",
+            "10"});
+            this.CMB_ratestatus.Location = new System.Drawing.Point(393, 242);
+            this.CMB_ratestatus.Name = "CMB_ratestatus";
+            this.CMB_ratestatus.Size = new System.Drawing.Size(40, 21);
+            this.CMB_ratestatus.TabIndex = 54;
+            this.CMB_ratestatus.SelectedIndexChanged += new System.EventHandler(this.CMB_ratestatus_SelectedIndexChanged);
+            // 
+            // CMB_rateposition
+            // 
+            this.CMB_rateposition.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CMB_rateposition.FormattingEnabled = true;
+            this.CMB_rateposition.Items.AddRange(new object[] {
+            "0",
+            "1",
+            "3",
+            "10"});
+            this.CMB_rateposition.Location = new System.Drawing.Point(273, 242);
+            this.CMB_rateposition.Name = "CMB_rateposition";
+            this.CMB_rateposition.Size = new System.Drawing.Size(40, 21);
+            this.CMB_rateposition.TabIndex = 55;
+            this.CMB_rateposition.SelectedIndexChanged += new System.EventHandler(this.CMB_rateposition_SelectedIndexChanged);
+            // 
+            // CMB_rateattitude
+            // 
+            this.CMB_rateattitude.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CMB_rateattitude.FormattingEnabled = true;
+            this.CMB_rateattitude.Items.AddRange(new object[] {
+            "0",
+            "1",
+            "3",
+            "10"});
+            this.CMB_rateattitude.Location = new System.Drawing.Point(173, 242);
+            this.CMB_rateattitude.Name = "CMB_rateattitude";
+            this.CMB_rateattitude.Size = new System.Drawing.Size(40, 21);
+            this.CMB_rateattitude.TabIndex = 56;
+            this.CMB_rateattitude.SelectedIndexChanged += new System.EventHandler(this.CMB_rateattitude_SelectedIndexChanged);
+            // 
+            // label99
+            // 
+            this.label99.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label99.Location = new System.Drawing.Point(268, 211);
+            this.label99.Name = "label99";
+            this.label99.Size = new System.Drawing.Size(402, 13);
+            this.label99.TabIndex = 57;
+            this.label99.Text = "NOTE: The Configuration Tab will NOT display these units, as those are raw values" +
+    ".\r\n";
+            // 
+            // label98
+            // 
+            this.label98.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label98.Location = new System.Drawing.Point(15, 219);
+            this.label98.Name = "label98";
+            this.label98.Size = new System.Drawing.Size(65, 13);
+            this.label98.TabIndex = 58;
+            this.label98.Text = "Speed Units";
+            // 
+            // label97
+            // 
+            this.label97.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label97.Location = new System.Drawing.Point(15, 191);
+            this.label97.Name = "label97";
+            this.label97.Size = new System.Drawing.Size(52, 13);
+            this.label97.TabIndex = 59;
+            this.label97.Text = "Dist Units";
+            // 
+            // CMB_speedunits
+            // 
+            this.CMB_speedunits.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CMB_speedunits.FormattingEnabled = true;
+            this.CMB_speedunits.Location = new System.Drawing.Point(124, 216);
+            this.CMB_speedunits.Name = "CMB_speedunits";
+            this.CMB_speedunits.Size = new System.Drawing.Size(138, 21);
+            this.CMB_speedunits.TabIndex = 60;
+            this.CMB_speedunits.SelectedIndexChanged += new System.EventHandler(this.CMB_speedunits_SelectedIndexChanged);
+            // 
+            // CMB_distunits
+            // 
+            this.CMB_distunits.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CMB_distunits.FormattingEnabled = true;
+            this.CMB_distunits.Location = new System.Drawing.Point(124, 189);
+            this.CMB_distunits.Name = "CMB_distunits";
+            this.CMB_distunits.Size = new System.Drawing.Size(138, 21);
+            this.CMB_distunits.TabIndex = 61;
+            this.CMB_distunits.SelectedIndexChanged += new System.EventHandler(this.CMB_distunits_SelectedIndexChanged);
+            // 
+            // label96
+            // 
+            this.label96.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label96.Location = new System.Drawing.Point(15, 164);
+            this.label96.Name = "label96";
+            this.label96.Size = new System.Drawing.Size(45, 13);
+            this.label96.TabIndex = 62;
+            this.label96.Text = "Joystick";
+            // 
+            // label95
+            // 
+            this.label95.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label95.Location = new System.Drawing.Point(15, 113);
+            this.label95.Name = "label95";
+            this.label95.Size = new System.Drawing.Size(44, 13);
+            this.label95.TabIndex = 63;
+            this.label95.Text = "Speech";
+            // 
+            // CHK_speechbattery
+            // 
+            this.CHK_speechbattery.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.CHK_speechbattery.Location = new System.Drawing.Point(456, 109);
+            this.CHK_speechbattery.Name = "CHK_speechbattery";
+            this.CHK_speechbattery.Size = new System.Drawing.Size(102, 17);
+            this.CHK_speechbattery.TabIndex = 64;
+            this.CHK_speechbattery.Text = "Battery Warning";
+            this.CHK_speechbattery.UseVisualStyleBackColor = true;
+            this.CHK_speechbattery.CheckedChanged += new System.EventHandler(this.CHK_speechbattery_CheckedChanged);
+            // 
+            // CHK_speechcustom
+            // 
+            this.CHK_speechcustom.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.CHK_speechcustom.Location = new System.Drawing.Point(363, 109);
+            this.CHK_speechcustom.Name = "CHK_speechcustom";
+            this.CHK_speechcustom.Size = new System.Drawing.Size(87, 17);
+            this.CHK_speechcustom.TabIndex = 65;
+            this.CHK_speechcustom.Text = "Time Interval";
+            this.CHK_speechcustom.UseVisualStyleBackColor = true;
+            this.CHK_speechcustom.CheckedChanged += new System.EventHandler(this.CHK_speechcustom_CheckedChanged);
+            // 
+            // CHK_speechmode
+            // 
+            this.CHK_speechmode.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.CHK_speechmode.Location = new System.Drawing.Point(307, 109);
+            this.CHK_speechmode.Name = "CHK_speechmode";
+            this.CHK_speechmode.Size = new System.Drawing.Size(56, 17);
+            this.CHK_speechmode.TabIndex = 66;
+            this.CHK_speechmode.Text = "Mode ";
+            this.CHK_speechmode.UseVisualStyleBackColor = true;
+            this.CHK_speechmode.CheckedChanged += new System.EventHandler(this.CHK_speechmode_CheckedChanged);
+            // 
+            // CHK_speechwaypoint
+            // 
+            this.CHK_speechwaypoint.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.CHK_speechwaypoint.Location = new System.Drawing.Point(230, 109);
+            this.CHK_speechwaypoint.Name = "CHK_speechwaypoint";
+            this.CHK_speechwaypoint.Size = new System.Drawing.Size(71, 17);
+            this.CHK_speechwaypoint.TabIndex = 67;
+            this.CHK_speechwaypoint.Text = "Waypoint";
+            this.CHK_speechwaypoint.UseVisualStyleBackColor = true;
+            this.CHK_speechwaypoint.CheckedChanged += new System.EventHandler(this.CHK_speechwaypoint_CheckedChanged);
+            // 
+            // label94
+            // 
+            this.label94.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label94.Location = new System.Drawing.Point(15, 85);
+            this.label94.Name = "label94";
+            this.label94.Size = new System.Drawing.Size(57, 13);
+            this.label94.TabIndex = 68;
+            this.label94.Text = "OSD Color";
+            // 
+            // CMB_osdcolor
+            // 
+            this.CMB_osdcolor.DrawMode = System.Windows.Forms.DrawMode.OwnerDrawFixed;
+            this.CMB_osdcolor.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CMB_osdcolor.FormattingEnabled = true;
+            this.CMB_osdcolor.Location = new System.Drawing.Point(124, 82);
+            this.CMB_osdcolor.Name = "CMB_osdcolor";
+            this.CMB_osdcolor.Size = new System.Drawing.Size(138, 21);
+            this.CMB_osdcolor.TabIndex = 69;
+            this.CMB_osdcolor.SelectedIndexChanged += new System.EventHandler(this.CMB_osdcolor_SelectedIndexChanged);
+            // 
+            // CMB_language
+            // 
+            this.CMB_language.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CMB_language.FormattingEnabled = true;
+            this.CMB_language.Location = new System.Drawing.Point(124, 133);
+            this.CMB_language.Name = "CMB_language";
+            this.CMB_language.Size = new System.Drawing.Size(138, 21);
+            this.CMB_language.TabIndex = 70;
+            this.CMB_language.SelectedIndexChanged += new System.EventHandler(this.CMB_language_SelectedIndexChanged);
+            // 
+            // label93
+            // 
+            this.label93.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label93.Location = new System.Drawing.Point(15, 137);
+            this.label93.Name = "label93";
+            this.label93.Size = new System.Drawing.Size(69, 13);
+            this.label93.TabIndex = 71;
+            this.label93.Text = "UI Language";
+            // 
+            // CHK_enablespeech
+            // 
+            this.CHK_enablespeech.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.CHK_enablespeech.Location = new System.Drawing.Point(124, 109);
+            this.CHK_enablespeech.Name = "CHK_enablespeech";
+            this.CHK_enablespeech.Size = new System.Drawing.Size(99, 17);
+            this.CHK_enablespeech.TabIndex = 72;
+            this.CHK_enablespeech.Text = "Enable Speech";
+            this.CHK_enablespeech.UseVisualStyleBackColor = true;
+            this.CHK_enablespeech.CheckedChanged += new System.EventHandler(this.CHK_enablespeech_CheckedChanged);
+            // 
+            // CHK_hudshow
+            // 
+            this.CHK_hudshow.Checked = true;
+            this.CHK_hudshow.CheckState = System.Windows.Forms.CheckState.Checked;
+            this.CHK_hudshow.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.CHK_hudshow.Location = new System.Drawing.Point(537, 17);
+            this.CHK_hudshow.Name = "CHK_hudshow";
+            this.CHK_hudshow.Size = new System.Drawing.Size(125, 17);
+            this.CHK_hudshow.TabIndex = 73;
+            this.CHK_hudshow.Text = "Enable HUD Overlay";
+            this.CHK_hudshow.UseVisualStyleBackColor = true;
+            this.CHK_hudshow.Click += new System.EventHandler(this.CHK_hudshow_CheckedChanged);
+            // 
+            // label92
+            // 
+            this.label92.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.label92.Location = new System.Drawing.Point(15, 18);
+            this.label92.Name = "label92";
+            this.label92.Size = new System.Drawing.Size(100, 23);
+            this.label92.TabIndex = 74;
+            this.label92.Text = "Video Device";
+            // 
+            // CMB_videosources
+            // 
+            this.CMB_videosources.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+            this.CMB_videosources.FormattingEnabled = true;
+            this.CMB_videosources.Location = new System.Drawing.Point(124, 15);
+            this.CMB_videosources.Name = "CMB_videosources";
+            this.CMB_videosources.Size = new System.Drawing.Size(245, 21);
+            this.CMB_videosources.TabIndex = 75;
+            this.CMB_videosources.SelectedIndexChanged += new System.EventHandler(this.CMB_videosources_SelectedIndexChanged);
+            // 
+            // BUT_Joystick
+            // 
+            this.BUT_Joystick.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.BUT_Joystick.Location = new System.Drawing.Point(124, 160);
+            this.BUT_Joystick.Name = "BUT_Joystick";
+            this.BUT_Joystick.Size = new System.Drawing.Size(99, 23);
+            this.BUT_Joystick.TabIndex = 76;
+            this.BUT_Joystick.Text = "Joystick Setup";
+            this.BUT_Joystick.UseVisualStyleBackColor = true;
+            this.BUT_Joystick.Click += new System.EventHandler(this.BUT_Joystick_Click);
+            // 
+            // BUT_videostop
+            // 
+            this.BUT_videostop.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.BUT_videostop.Location = new System.Drawing.Point(456, 13);
+            this.BUT_videostop.Name = "BUT_videostop";
+            this.BUT_videostop.Size = new System.Drawing.Size(75, 23);
+            this.BUT_videostop.TabIndex = 77;
+            this.BUT_videostop.Text = "Stop";
+            this.BUT_videostop.UseVisualStyleBackColor = true;
+            this.BUT_videostop.Click += new System.EventHandler(this.BUT_videostop_Click);
+            // 
+            // BUT_videostart
+            // 
+            this.BUT_videostart.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.BUT_videostart.Location = new System.Drawing.Point(375, 13);
+            this.BUT_videostart.Name = "BUT_videostart";
+            this.BUT_videostart.Size = new System.Drawing.Size(75, 23);
+            this.BUT_videostart.TabIndex = 78;
+            this.BUT_videostart.Text = "Start";
+            this.BUT_videostart.UseVisualStyleBackColor = true;
+            this.BUT_videostart.Click += new System.EventHandler(this.BUT_videostart_Click);
+            // 
+            // ConfigPlanner
+            // 
+            this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
+            this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+            this.Controls.Add(this.label33);
+            this.Controls.Add(this.CMB_ratesensors);
+            this.Controls.Add(this.label26);
+            this.Controls.Add(this.CMB_videoresolutions);
+            this.Controls.Add(this.label12);
+            this.Controls.Add(this.CHK_GDIPlus);
+            this.Controls.Add(this.label24);
+            this.Controls.Add(this.CHK_loadwponconnect);
+            this.Controls.Add(this.label23);
+            this.Controls.Add(this.NUM_tracklength);
+            this.Controls.Add(this.CHK_speechaltwarning);
+            this.Controls.Add(this.label108);
+            this.Controls.Add(this.CHK_resetapmonconnect);
+            this.Controls.Add(this.CHK_mavdebug);
+            this.Controls.Add(this.label107);
+            this.Controls.Add(this.CMB_raterc);
+            this.Controls.Add(this.label104);
+            this.Controls.Add(this.label103);
+            this.Controls.Add(this.label102);
+            this.Controls.Add(this.label101);
+            this.Controls.Add(this.CMB_ratestatus);
+            this.Controls.Add(this.CMB_rateposition);
+            this.Controls.Add(this.CMB_rateattitude);
+            this.Controls.Add(this.label99);
+            this.Controls.Add(this.label98);
+            this.Controls.Add(this.label97);
+            this.Controls.Add(this.CMB_speedunits);
+            this.Controls.Add(this.CMB_distunits);
+            this.Controls.Add(this.label96);
+            this.Controls.Add(this.label95);
+            this.Controls.Add(this.CHK_speechbattery);
+            this.Controls.Add(this.CHK_speechcustom);
+            this.Controls.Add(this.CHK_speechmode);
+            this.Controls.Add(this.CHK_speechwaypoint);
+            this.Controls.Add(this.label94);
+            this.Controls.Add(this.CMB_osdcolor);
+            this.Controls.Add(this.CMB_language);
+            this.Controls.Add(this.label93);
+            this.Controls.Add(this.CHK_enablespeech);
+            this.Controls.Add(this.CHK_hudshow);
+            this.Controls.Add(this.label92);
+            this.Controls.Add(this.CMB_videosources);
+            this.Controls.Add(this.BUT_Joystick);
+            this.Controls.Add(this.BUT_videostop);
+            this.Controls.Add(this.BUT_videostart);
+            this.Name = "ConfigPlanner";
+            this.Size = new System.Drawing.Size(682, 398);
+            ((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).EndInit();
+            this.ResumeLayout(false);
+
+        }
+
+        #endregion
+
+        private System.Windows.Forms.Label label33;
+        private System.Windows.Forms.ComboBox CMB_ratesensors;
+        private System.Windows.Forms.Label label26;
+        private System.Windows.Forms.ComboBox CMB_videoresolutions;
+        private System.Windows.Forms.Label label12;
+        private System.Windows.Forms.CheckBox CHK_GDIPlus;
+        private System.Windows.Forms.Label label24;
+        private System.Windows.Forms.CheckBox CHK_loadwponconnect;
+        private System.Windows.Forms.Label label23;
+        private System.Windows.Forms.NumericUpDown NUM_tracklength;
+        private System.Windows.Forms.CheckBox CHK_speechaltwarning;
+        private System.Windows.Forms.Label label108;
+        private System.Windows.Forms.CheckBox CHK_resetapmonconnect;
+        private System.Windows.Forms.CheckBox CHK_mavdebug;
+        private System.Windows.Forms.Label label107;
+        private System.Windows.Forms.ComboBox CMB_raterc;
+        private System.Windows.Forms.Label label104;
+        private System.Windows.Forms.Label label103;
+        private System.Windows.Forms.Label label102;
+        private System.Windows.Forms.Label label101;
+        private System.Windows.Forms.ComboBox CMB_ratestatus;
+        private System.Windows.Forms.ComboBox CMB_rateposition;
+        private System.Windows.Forms.ComboBox CMB_rateattitude;
+        private System.Windows.Forms.Label label99;
+        private System.Windows.Forms.Label label98;
+        private System.Windows.Forms.Label label97;
+        private System.Windows.Forms.ComboBox CMB_speedunits;
+        private System.Windows.Forms.ComboBox CMB_distunits;
+        private System.Windows.Forms.Label label96;
+        private System.Windows.Forms.Label label95;
+        private System.Windows.Forms.CheckBox CHK_speechbattery;
+        private System.Windows.Forms.CheckBox CHK_speechcustom;
+        private System.Windows.Forms.CheckBox CHK_speechmode;
+        private System.Windows.Forms.CheckBox CHK_speechwaypoint;
+        private System.Windows.Forms.Label label94;
+        private System.Windows.Forms.ComboBox CMB_osdcolor;
+        private System.Windows.Forms.ComboBox CMB_language;
+        private System.Windows.Forms.Label label93;
+        private System.Windows.Forms.CheckBox CHK_enablespeech;
+        private System.Windows.Forms.CheckBox CHK_hudshow;
+        private System.Windows.Forms.Label label92;
+        private System.Windows.Forms.ComboBox CMB_videosources;
+        private MyButton BUT_Joystick;
+        private MyButton BUT_videostop;
+        private MyButton BUT_videostart;
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs
new file mode 100644
index 0000000000000000000000000000000000000000..f09ac19d4cccc72176b6a964d880a04d898fcbd2
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs
@@ -0,0 +1,373 @@
+using System;
+using System.Collections.Generic;
+using System.ComponentModel;
+using System.Drawing;
+using System.Data;
+using System.Globalization;
+using System.Linq;
+using System.Runtime.InteropServices;
+using System.Text;
+using System.Windows.Forms;
+using DirectShowLib;
+using ArdupilotMega.Controls.BackstageView;
+
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    public partial class ConfigPlanner : BackStageViewContentPanel
+    {
+        // AR todo: replicate this functionality
+        private bool startup = false;
+
+        public ConfigPlanner()
+        {
+            InitializeComponent();
+        }
+
+
+        private void BUT_videostart_Click(object sender, EventArgs e)
+        {
+            // stop first
+            BUT_videostop_Click(sender, e);
+
+            var bmp = (GCSViews.Configuration.GCSBitmapInfo)CMB_videoresolutions.SelectedItem;
+
+            try
+            {
+                MainV2.cam = new WebCamService.Capture(CMB_videosources.SelectedIndex, bmp.Media);
+
+                MainV2.cam.showhud = CHK_hudshow.Checked;
+
+                MainV2.cam.Start();
+
+                MainV2.config["video_options"] = CMB_videoresolutions.SelectedIndex;
+
+                BUT_videostart.Enabled = false;
+            }
+            catch (Exception ex) { CustomMessageBox.Show("Camera Fail: " + ex.Message); }
+
+        }
+
+        private void BUT_videostop_Click(object sender, EventArgs e)
+        {
+            BUT_videostart.Enabled = true;
+            if (MainV2.cam != null)
+            {
+                MainV2.cam.Dispose();
+                MainV2.cam = null;
+            }
+        }
+
+        private void CMB_videosources_MouseClick(object sender, MouseEventArgs e)
+        {
+            // the reason why i dont populate this list is because on linux/mac this call will fail.
+            WebCamService.Capture capt = new WebCamService.Capture();
+
+            List<string> devices = WebCamService.Capture.getDevices();
+
+            CMB_videosources.DataSource = devices;
+
+            capt.Dispose();
+        }
+
+        private void CMB_videosources_SelectedIndexChanged(object sender, EventArgs e)
+        {
+            int hr;
+            int count;
+            int size;
+            object o;
+            IBaseFilter capFilter = null;
+            ICaptureGraphBuilder2 capGraph = null;
+            AMMediaType media = null;
+            VideoInfoHeader v;
+            VideoStreamConfigCaps c;
+            List<GCSViews.Configuration.GCSBitmapInfo> modes = new List<GCSViews.Configuration.GCSBitmapInfo>();
+
+            // Get the ICaptureGraphBuilder2
+            capGraph = (ICaptureGraphBuilder2)new CaptureGraphBuilder2();
+            IFilterGraph2 m_FilterGraph = (IFilterGraph2)new FilterGraph();
+
+            DsDevice[] capDevices;
+            capDevices = DsDevice.GetDevicesOfCat(FilterCategory.VideoInputDevice);
+
+            // Add the video device
+            hr = m_FilterGraph.AddSourceFilterForMoniker(capDevices[CMB_videosources.SelectedIndex].Mon, null, "Video input", out capFilter);
+            try
+            {
+                DsError.ThrowExceptionForHR(hr);
+            }
+            catch (Exception ex)
+            {
+                CustomMessageBox.Show("Can not add video source\n" + ex.ToString());
+                return;
+            }
+
+            // Find the stream config interface
+            hr = capGraph.FindInterface(PinCategory.Capture, MediaType.Video, capFilter, typeof(IAMStreamConfig).GUID, out o);
+            DsError.ThrowExceptionForHR(hr);
+
+            IAMStreamConfig videoStreamConfig = o as IAMStreamConfig;
+            if (videoStreamConfig == null)
+            {
+                throw new Exception("Failed to get IAMStreamConfig");
+            }
+
+            hr = videoStreamConfig.GetNumberOfCapabilities(out count, out size);
+            DsError.ThrowExceptionForHR(hr);
+            IntPtr TaskMemPointer = Marshal.AllocCoTaskMem(size);
+            for (int i = 0; i < count; i++)
+            {
+                IntPtr ptr = IntPtr.Zero;
+
+                hr = videoStreamConfig.GetStreamCaps(i, out media, TaskMemPointer);
+                v = (VideoInfoHeader)Marshal.PtrToStructure(media.formatPtr, typeof(VideoInfoHeader));
+                c = (VideoStreamConfigCaps)Marshal.PtrToStructure(TaskMemPointer, typeof(VideoStreamConfigCaps));
+                modes.Add(new GCSViews.Configuration.GCSBitmapInfo(v.BmiHeader.Width, v.BmiHeader.Height, c.MaxFrameInterval, c.VideoStandard.ToString(), media));
+            }
+            Marshal.FreeCoTaskMem(TaskMemPointer);
+            DsUtils.FreeAMMediaType(media);
+
+            CMB_videoresolutions.DataSource = modes;
+
+            if (MainV2.getConfig("video_options") != "" && CMB_videosources.Text != "")
+            {
+                CMB_videoresolutions.SelectedIndex = int.Parse(MainV2.getConfig("video_options"));
+            }
+        }
+
+        private void CHK_hudshow_CheckedChanged(object sender, EventArgs e)
+        {
+            GCSViews.FlightData.myhud.hudon = CHK_hudshow.Checked;
+        }
+
+        private void CHK_enablespeech_CheckedChanged(object sender, EventArgs e)
+        {
+            MainV2.speechEnable = CHK_enablespeech.Checked;
+            MainV2.config["speechenable"] = CHK_enablespeech.Checked;
+            if (MainV2.speechEngine != null)
+                MainV2.speechEngine.SpeakAsyncCancelAll();
+        }
+
+        private void CMB_language_SelectedIndexChanged(object sender, EventArgs e)
+        {
+            MainV2.instance.changelanguage((CultureInfo)CMB_language.SelectedItem);
+
+#if !DEBUG
+                MessageBox.Show("Please Restart the Planner");
+
+                Application.Exit();
+#endif
+        }
+
+        private void CMB_osdcolor_SelectedIndexChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            if (CMB_osdcolor.Text != "")
+            {
+                MainV2.config["hudcolor"] = CMB_osdcolor.Text;
+                GCSViews.FlightData.myhud.hudcolor = Color.FromKnownColor((KnownColor)Enum.Parse(typeof(KnownColor), CMB_osdcolor.Text));
+            }
+        }
+
+        private void CHK_speechwaypoint_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            MainV2.config["speechwaypointenabled"] = ((CheckBox)sender).Checked.ToString();
+
+            if (((CheckBox)sender).Checked)
+            {
+                string speechstring = "Heading to Waypoint {wpn}";
+                if (MainV2.config["speechwaypoint"] != null)
+                    speechstring = MainV2.config["speechwaypoint"].ToString();
+                Common.InputBox("Notification", "What do you want it to say?", ref speechstring);
+                MainV2.config["speechwaypoint"] = speechstring;
+            }
+        }
+
+        private void CHK_speechmode_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            MainV2.config["speechmodeenabled"] = ((CheckBox)sender).Checked.ToString();
+
+            if (((CheckBox)sender).Checked)
+            {
+                string speechstring = "Mode changed to {mode}";
+                if (MainV2.config["speechmode"] != null)
+                    speechstring = MainV2.config["speechmode"].ToString();
+                Common.InputBox("Notification", "What do you want it to say?", ref speechstring);
+                MainV2.config["speechmode"] = speechstring;
+            }
+        }
+
+        private void CHK_speechcustom_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            MainV2.config["speechcustomenabled"] = ((CheckBox)sender).Checked.ToString();
+
+            if (((CheckBox)sender).Checked)
+            {
+                string speechstring = "Heading to Waypoint {wpn}, altitude is {alt}, Ground speed is {gsp} ";
+                if (MainV2.config["speechcustom"] != null)
+                    speechstring = MainV2.config["speechcustom"].ToString();
+                Common.InputBox("Notification", "What do you want it to say?", ref speechstring);
+                MainV2.config["speechcustom"] = speechstring;
+            }
+        }
+
+        private void BUT_rerequestparams_Click(object sender, EventArgs e)
+        {
+            if (!MainV2.comPort.BaseStream.IsOpen)
+                return;
+            ((MyButton)sender).Enabled = false;
+            try
+            {
+
+                MainV2.comPort.getParamList();
+
+
+
+
+            }
+            catch { CustomMessageBox.Show("Error: getting param list"); }
+
+
+            ((MyButton)sender).Enabled = true;
+            startup = true;
+
+            // AR todo: fix this up
+            //Configuration_Load(null, null);
+        }
+
+        private void CHK_speechbattery_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            MainV2.config["speechbatteryenabled"] = ((CheckBox)sender).Checked.ToString();
+
+            if (((CheckBox)sender).Checked)
+            {
+                string speechstring = "WARNING, Battery at {batv} Volt";
+                if (MainV2.config["speechbattery"] != null)
+                    speechstring = MainV2.config["speechbattery"].ToString();
+                Common.InputBox("Notification", "What do you want it to say?", ref speechstring);
+                MainV2.config["speechbattery"] = speechstring;
+
+                speechstring = "9.6";
+                if (MainV2.config["speechbatteryvolt"] != null)
+                    speechstring = MainV2.config["speechbatteryvolt"].ToString();
+                Common.InputBox("Battery Level", "What Voltage do you want to warn at?", ref speechstring);
+                MainV2.config["speechbatteryvolt"] = speechstring;
+
+            }
+        }
+
+        private void BUT_Joystick_Click(object sender, EventArgs e)
+        {
+            Form joy = new JoystickSetup();
+            ThemeManager.ApplyThemeTo(joy);
+            joy.Show();
+        }
+
+        private void CMB_distunits_SelectedIndexChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            MainV2.config["distunits"] = CMB_distunits.Text;
+            MainV2.instance.changeunits();
+        }
+
+        private void CMB_speedunits_SelectedIndexChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            MainV2.config["speedunits"] = CMB_speedunits.Text;
+            MainV2.instance.changeunits();
+        }
+
+        private void CMB_rateattitude_SelectedIndexChanged(object sender, EventArgs e)
+        {
+            MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
+            MainV2.cs.rateattitude = byte.Parse(((ComboBox)sender).Text);
+        }
+
+        private void CMB_rateposition_SelectedIndexChanged(object sender, EventArgs e)
+        {
+            MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
+            MainV2.cs.rateposition = byte.Parse(((ComboBox)sender).Text);
+        }
+
+        private void CMB_ratestatus_SelectedIndexChanged(object sender, EventArgs e)
+        {
+            MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
+            MainV2.cs.ratestatus = byte.Parse(((ComboBox)sender).Text);
+        }
+
+        private void CMB_raterc_SelectedIndexChanged(object sender, EventArgs e)
+        {
+            MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
+            MainV2.cs.raterc = byte.Parse(((ComboBox)sender).Text);
+        }
+
+        private void CMB_ratesensors_SelectedIndexChanged(object sender, EventArgs e)
+        {
+            MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
+            MainV2.cs.ratesensors = byte.Parse(((ComboBox)sender).Text);
+        }
+
+        private void CHK_mavdebug_CheckedChanged(object sender, EventArgs e)
+        {
+            MainV2.comPort.debugmavlink = CHK_mavdebug.Checked;
+        }
+
+        private void CHK_resetapmonconnect_CheckedChanged(object sender, EventArgs e)
+        {
+            MainV2.config[((CheckBox)sender).Name] = ((CheckBox)sender).Checked.ToString();
+        }
+
+        private void CHK_speechaltwarning_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            MainV2.config["speechaltenabled"] = ((CheckBox)sender).Checked.ToString();
+
+            if (((CheckBox)sender).Checked)
+            {
+                string speechstring = "WARNING, low altitude {alt}";
+                if (MainV2.config["speechalt"] != null)
+                    speechstring = MainV2.config["speechalt"].ToString();
+                Common.InputBox("Notification", "What do you want it to say?", ref speechstring);
+                MainV2.config["speechalt"] = speechstring;
+
+                speechstring = "2";
+                if (MainV2.config["speechaltheight"] != null)
+                    speechstring = MainV2.config["speechaltheight"].ToString();
+                Common.InputBox("Min Alt", "What altitude do you want to warn at? (relative to home)", ref speechstring);
+                MainV2.config["speechaltheight"] = (double.Parse(speechstring) / MainV2.cs.multiplierdist).ToString(); // save as m
+
+            }
+        }
+
+        private void NUM_tracklength_ValueChanged(object sender, EventArgs e)
+        {
+            MainV2.config["NUM_tracklength"] = NUM_tracklength.Value.ToString();
+
+        }
+
+        private void CHK_loadwponconnect_CheckedChanged(object sender, EventArgs e)
+        {
+            MainV2.config["loadwpsonconnect"] = CHK_loadwponconnect.Checked.ToString();
+        }
+
+        private void CHK_GDIPlus_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            CustomMessageBox.Show("You need to restart the planner for this to take effect");
+            MainV2.config["CHK_GDIPlus"] = CHK_GDIPlus.Checked.ToString();
+        }
+
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx
new file mode 100644
index 0000000000000000000000000000000000000000..7080a7d118e8cd7ec668e9bb0d8e90767e0c7a3c
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx
@@ -0,0 +1,120 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs
new file mode 100644
index 0000000000000000000000000000000000000000..f3e54cffe31d01144b2001ac5dcbe644f903340e
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs
@@ -0,0 +1,303 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    partial class ConfigRadioInput
+    {
+        /// <summary> 
+        /// Required designer variable.
+        /// </summary>
+        private System.ComponentModel.IContainer components = null;
+
+        /// <summary> 
+        /// Clean up any resources being used.
+        /// </summary>
+        /// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
+        protected override void Dispose(bool disposing)
+        {
+            if (disposing && (components != null))
+            {
+                components.Dispose();
+            }
+            base.Dispose(disposing);
+        }
+
+        #region Component Designer generated code
+
+        /// <summary> 
+        /// Required method for Designer support - do not modify 
+        /// the contents of this method with the code editor.
+        /// </summary>
+        private void InitializeComponent()
+        {
+            this.components = new System.ComponentModel.Container();
+            System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigRadioInput));
+            this.groupBoxElevons = new System.Windows.Forms.GroupBox();
+            this.CHK_mixmode = new System.Windows.Forms.CheckBox();
+            this.CHK_elevonch2rev = new System.Windows.Forms.CheckBox();
+            this.CHK_elevonrev = new System.Windows.Forms.CheckBox();
+            this.CHK_elevonch1rev = new System.Windows.Forms.CheckBox();
+            this.CHK_revch3 = new System.Windows.Forms.CheckBox();
+            this.CHK_revch4 = new System.Windows.Forms.CheckBox();
+            this.CHK_revch2 = new System.Windows.Forms.CheckBox();
+            this.CHK_revch1 = new System.Windows.Forms.CheckBox();
+            this.BUT_Calibrateradio = new ArdupilotMega.MyButton();
+            this.BAR8 = new ArdupilotMega.HorizontalProgressBar2();
+            this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components);
+            this.BAR7 = new ArdupilotMega.HorizontalProgressBar2();
+            this.BAR6 = new ArdupilotMega.HorizontalProgressBar2();
+            this.BAR5 = new ArdupilotMega.HorizontalProgressBar2();
+            this.BARpitch = new ArdupilotMega.VerticalProgressBar2();
+            this.BARthrottle = new ArdupilotMega.VerticalProgressBar2();
+            this.BARyaw = new ArdupilotMega.HorizontalProgressBar2();
+            this.BARroll = new ArdupilotMega.HorizontalProgressBar2();
+            this.groupBoxElevons.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit();
+            this.SuspendLayout();
+            // 
+            // groupBoxElevons
+            // 
+            this.groupBoxElevons.Controls.Add(this.CHK_mixmode);
+            this.groupBoxElevons.Controls.Add(this.CHK_elevonch2rev);
+            this.groupBoxElevons.Controls.Add(this.CHK_elevonrev);
+            this.groupBoxElevons.Controls.Add(this.CHK_elevonch1rev);
+            resources.ApplyResources(this.groupBoxElevons, "groupBoxElevons");
+            this.groupBoxElevons.Name = "groupBoxElevons";
+            this.groupBoxElevons.TabStop = false;
+            // 
+            // CHK_mixmode
+            // 
+            resources.ApplyResources(this.CHK_mixmode, "CHK_mixmode");
+            this.CHK_mixmode.Name = "CHK_mixmode";
+            this.CHK_mixmode.UseVisualStyleBackColor = true;
+            this.CHK_mixmode.CheckedChanged += new System.EventHandler(this.CHK_mixmode_CheckedChanged);
+            // 
+            // CHK_elevonch2rev
+            // 
+            resources.ApplyResources(this.CHK_elevonch2rev, "CHK_elevonch2rev");
+            this.CHK_elevonch2rev.Name = "CHK_elevonch2rev";
+            this.CHK_elevonch2rev.UseVisualStyleBackColor = true;
+            this.CHK_elevonch2rev.CheckedChanged += new System.EventHandler(this.CHK_elevonch2rev_CheckedChanged);
+            // 
+            // CHK_elevonrev
+            // 
+            resources.ApplyResources(this.CHK_elevonrev, "CHK_elevonrev");
+            this.CHK_elevonrev.Name = "CHK_elevonrev";
+            this.CHK_elevonrev.UseVisualStyleBackColor = true;
+            this.CHK_elevonrev.CheckedChanged += new System.EventHandler(this.CHK_elevonrev_CheckedChanged);
+            // 
+            // CHK_elevonch1rev
+            // 
+            resources.ApplyResources(this.CHK_elevonch1rev, "CHK_elevonch1rev");
+            this.CHK_elevonch1rev.Name = "CHK_elevonch1rev";
+            this.CHK_elevonch1rev.UseVisualStyleBackColor = true;
+            this.CHK_elevonch1rev.CheckedChanged += new System.EventHandler(this.CHK_elevonch1rev_CheckedChanged);
+            // 
+            // CHK_revch3
+            // 
+            resources.ApplyResources(this.CHK_revch3, "CHK_revch3");
+            this.CHK_revch3.Name = "CHK_revch3";
+            this.CHK_revch3.UseVisualStyleBackColor = true;
+            this.CHK_revch3.CheckedChanged += new System.EventHandler(this.CHK_revch3_CheckedChanged);
+            // 
+            // CHK_revch4
+            // 
+            resources.ApplyResources(this.CHK_revch4, "CHK_revch4");
+            this.CHK_revch4.Name = "CHK_revch4";
+            this.CHK_revch4.UseVisualStyleBackColor = true;
+            this.CHK_revch4.CheckedChanged += new System.EventHandler(this.CHK_revch4_CheckedChanged);
+            // 
+            // CHK_revch2
+            // 
+            resources.ApplyResources(this.CHK_revch2, "CHK_revch2");
+            this.CHK_revch2.Name = "CHK_revch2";
+            this.CHK_revch2.UseVisualStyleBackColor = true;
+            this.CHK_revch2.CheckedChanged += new System.EventHandler(this.CHK_revch2_CheckedChanged);
+            // 
+            // CHK_revch1
+            // 
+            resources.ApplyResources(this.CHK_revch1, "CHK_revch1");
+            this.CHK_revch1.Name = "CHK_revch1";
+            this.CHK_revch1.UseVisualStyleBackColor = true;
+            this.CHK_revch1.CheckedChanged += new System.EventHandler(this.CHK_revch1_CheckedChanged);
+            // 
+            // BUT_Calibrateradio
+            // 
+            resources.ApplyResources(this.BUT_Calibrateradio, "BUT_Calibrateradio");
+            this.BUT_Calibrateradio.Name = "BUT_Calibrateradio";
+            this.BUT_Calibrateradio.UseVisualStyleBackColor = true;
+            this.BUT_Calibrateradio.Click += new System.EventHandler(this.BUT_Calibrateradio_Click);
+            // 
+            // BAR8
+            // 
+            this.BAR8.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
+            this.BAR8.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+            this.BAR8.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch8in", true));
+            this.BAR8.Label = "Radio 8";
+            resources.ApplyResources(this.BAR8, "BAR8");
+            this.BAR8.Maximum = 2200;
+            this.BAR8.maxline = 0;
+            this.BAR8.Minimum = 800;
+            this.BAR8.minline = 0;
+            this.BAR8.Name = "BAR8";
+            this.BAR8.Value = 1500;
+            this.BAR8.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
+            // 
+            // currentStateBindingSource
+            // 
+            this.currentStateBindingSource.DataSource = typeof(ArdupilotMega.CurrentState);
+            // 
+            // BAR7
+            // 
+            this.BAR7.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
+            this.BAR7.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+            this.BAR7.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch7in", true));
+            this.BAR7.Label = "Radio 7";
+            resources.ApplyResources(this.BAR7, "BAR7");
+            this.BAR7.Maximum = 2200;
+            this.BAR7.maxline = 0;
+            this.BAR7.Minimum = 800;
+            this.BAR7.minline = 0;
+            this.BAR7.Name = "BAR7";
+            this.BAR7.Value = 1500;
+            this.BAR7.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
+            // 
+            // BAR6
+            // 
+            this.BAR6.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
+            this.BAR6.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+            this.BAR6.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch6in", true));
+            this.BAR6.Label = "Radio 6";
+            resources.ApplyResources(this.BAR6, "BAR6");
+            this.BAR6.Maximum = 2200;
+            this.BAR6.maxline = 0;
+            this.BAR6.Minimum = 800;
+            this.BAR6.minline = 0;
+            this.BAR6.Name = "BAR6";
+            this.BAR6.Value = 1500;
+            this.BAR6.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
+            // 
+            // BAR5
+            // 
+            this.BAR5.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
+            this.BAR5.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+            this.BAR5.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch5in", true));
+            this.BAR5.Label = "Radio 5";
+            resources.ApplyResources(this.BAR5, "BAR5");
+            this.BAR5.Maximum = 2200;
+            this.BAR5.maxline = 0;
+            this.BAR5.Minimum = 800;
+            this.BAR5.minline = 0;
+            this.BAR5.Name = "BAR5";
+            this.BAR5.Value = 1500;
+            this.BAR5.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
+            // 
+            // BARpitch
+            // 
+            this.BARpitch.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
+            this.BARpitch.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+            this.BARpitch.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch2in", true));
+            this.BARpitch.Label = "Pitch";
+            resources.ApplyResources(this.BARpitch, "BARpitch");
+            this.BARpitch.Maximum = 2200;
+            this.BARpitch.maxline = 0;
+            this.BARpitch.Minimum = 800;
+            this.BARpitch.minline = 0;
+            this.BARpitch.Name = "BARpitch";
+            this.BARpitch.Value = 1500;
+            this.BARpitch.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
+            // 
+            // BARthrottle
+            // 
+            this.BARthrottle.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
+            this.BARthrottle.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+            this.BARthrottle.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch3in", true));
+            this.BARthrottle.Label = "Throttle";
+            resources.ApplyResources(this.BARthrottle, "BARthrottle");
+            this.BARthrottle.Maximum = 2200;
+            this.BARthrottle.maxline = 0;
+            this.BARthrottle.Minimum = 800;
+            this.BARthrottle.minline = 0;
+            this.BARthrottle.Name = "BARthrottle";
+            this.BARthrottle.Value = 1000;
+            this.BARthrottle.ValueColor = System.Drawing.Color.Magenta;
+            // 
+            // BARyaw
+            // 
+            this.BARyaw.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
+            this.BARyaw.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+            this.BARyaw.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch4in", true));
+            this.BARyaw.Label = "Yaw";
+            resources.ApplyResources(this.BARyaw, "BARyaw");
+            this.BARyaw.Maximum = 2200;
+            this.BARyaw.maxline = 0;
+            this.BARyaw.Minimum = 800;
+            this.BARyaw.minline = 0;
+            this.BARyaw.Name = "BARyaw";
+            this.BARyaw.Value = 1500;
+            this.BARyaw.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
+            // 
+            // BARroll
+            // 
+            this.BARroll.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
+            this.BARroll.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+            this.BARroll.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch1in", true));
+            this.BARroll.Label = "Roll";
+            resources.ApplyResources(this.BARroll, "BARroll");
+            this.BARroll.Maximum = 2200;
+            this.BARroll.maxline = 0;
+            this.BARroll.Minimum = 800;
+            this.BARroll.minline = 0;
+            this.BARroll.Name = "BARroll";
+            this.BARroll.Value = 1500;
+            this.BARroll.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
+            // 
+            // ConfigRadioInput
+            // 
+            resources.ApplyResources(this, "$this");
+            this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+            this.Controls.Add(this.groupBoxElevons);
+            this.Controls.Add(this.CHK_revch3);
+            this.Controls.Add(this.CHK_revch4);
+            this.Controls.Add(this.CHK_revch2);
+            this.Controls.Add(this.CHK_revch1);
+            this.Controls.Add(this.BUT_Calibrateradio);
+            this.Controls.Add(this.BAR8);
+            this.Controls.Add(this.BAR7);
+            this.Controls.Add(this.BAR6);
+            this.Controls.Add(this.BAR5);
+            this.Controls.Add(this.BARpitch);
+            this.Controls.Add(this.BARthrottle);
+            this.Controls.Add(this.BARyaw);
+            this.Controls.Add(this.BARroll);
+            this.Name = "ConfigRadioInput";
+            this.Load += new System.EventHandler(this.ConfigRadioInput_Load);
+            this.groupBoxElevons.ResumeLayout(false);
+            this.groupBoxElevons.PerformLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit();
+            this.ResumeLayout(false);
+            this.PerformLayout();
+
+        }
+
+        #endregion
+
+        private System.Windows.Forms.GroupBox groupBoxElevons;
+        private System.Windows.Forms.CheckBox CHK_mixmode;
+        private System.Windows.Forms.CheckBox CHK_elevonch2rev;
+        private System.Windows.Forms.CheckBox CHK_elevonrev;
+        private System.Windows.Forms.CheckBox CHK_elevonch1rev;
+        private System.Windows.Forms.CheckBox CHK_revch3;
+        private System.Windows.Forms.CheckBox CHK_revch4;
+        private System.Windows.Forms.CheckBox CHK_revch2;
+        private System.Windows.Forms.CheckBox CHK_revch1;
+        private MyButton BUT_Calibrateradio;
+        private HorizontalProgressBar2 BAR8;
+        private HorizontalProgressBar2 BAR7;
+        private HorizontalProgressBar2 BAR6;
+        private HorizontalProgressBar2 BAR5;
+        private VerticalProgressBar2 BARpitch;
+        private VerticalProgressBar2 BARthrottle;
+        private HorizontalProgressBar2 BARyaw;
+        private HorizontalProgressBar2 BARroll;
+        private System.Windows.Forms.BindingSource currentStateBindingSource;
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs
new file mode 100644
index 0000000000000000000000000000000000000000..91e6716fe9283c875a43b0715c416f1250124e2e
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs
@@ -0,0 +1,368 @@
+using System;
+using System.Collections.Generic;
+using System.ComponentModel;
+using System.Drawing;
+using System.Data;
+using System.Linq;
+using System.Text;
+using System.Windows.Forms;
+using ArdupilotMega.Controls.BackstageView;
+
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    public partial class ConfigRadioInput : BackStageViewContentPanel
+    {
+        bool startup = false;
+        bool run = false;
+
+        float[] rcmin = new float[8];
+        float[] rcmax = new float[8];
+        float[] rctrim = new float[8];
+
+        Timer timer = new Timer();
+
+        public ConfigRadioInput()
+        {
+            InitializeComponent();
+
+            // setup rc calib extents
+            for (int a = 0; a < rcmin.Length; a++)
+            {
+                rcmin[a] = 3000;
+                rcmax[a] = 0;
+                rctrim[a] = 1500;
+            }
+
+            // setup rc update
+            timer.Tick += new EventHandler(timer_Tick);
+
+            timer.Enabled = true;
+            timer.Interval = 100;
+            timer.Start();
+        }
+
+        void timer_Tick(object sender, EventArgs e)
+        {
+            // update all linked controls - 10hz
+            try
+            {
+                MainV2.cs.UpdateCurrentSettings(currentStateBindingSource);
+            }
+            catch { }
+        }
+
+        private void ConfigRadioInput_Load(object sender, EventArgs e)
+        {
+            if (!MainV2.comPort.BaseStream.IsOpen)
+            {
+                this.Enabled = false;
+                return;
+            }
+            else
+            {
+                this.Enabled = true;
+            }
+
+            startup = true;
+
+            if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
+            {
+                groupBoxElevons.Visible = false;
+            }
+            else
+            {
+                try
+                {
+                    CHK_mixmode.Checked = MainV2.comPort.param["ELEVON_MIXING"].ToString() == "1";
+                    CHK_elevonrev.Checked = MainV2.comPort.param["ELEVON_REVERSE"].ToString() == "1";
+                    CHK_elevonch1rev.Checked = MainV2.comPort.param["ELEVON_CH1_REV"].ToString() == "1";
+                    CHK_elevonch2rev.Checked = MainV2.comPort.param["ELEVON_CH2_REV"].ToString() == "1";
+                }
+                catch { } // this will fail on arducopter
+            }
+            try
+            {
+                CHK_revch1.Checked = MainV2.comPort.param["RC1_REV"].ToString() == "-1";
+                CHK_revch2.Checked = MainV2.comPort.param["RC2_REV"].ToString() == "-1";
+                CHK_revch3.Checked = MainV2.comPort.param["RC3_REV"].ToString() == "-1";
+                CHK_revch4.Checked = MainV2.comPort.param["RC4_REV"].ToString() == "-1";
+            }
+            catch (Exception ex) { CustomMessageBox.Show("Missing RC rev Param " + ex.ToString()); }
+            startup = false;
+        }
+
+        private void BUT_Calibrateradio_Click(object sender, EventArgs e)
+        {
+            if (run)
+            {
+                BUT_Calibrateradio.Text = "Completed";
+                run = false;
+                return;
+            }
+
+            CustomMessageBox.Show("Ensure your transmitter is on and receiver is powered and connected\nEnsure your motor does not have power/no props!!!");
+
+            byte oldrc = MainV2.cs.raterc;
+            byte oldatt = MainV2.cs.rateattitude;
+            byte oldpos = MainV2.cs.rateposition;
+            byte oldstatus = MainV2.cs.ratestatus;
+
+            MainV2.cs.raterc = 10;
+            MainV2.cs.rateattitude = 0;
+            MainV2.cs.rateposition = 0;
+            MainV2.cs.ratestatus = 0;
+
+            try
+            {
+
+                MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RC_CHANNELS, 10);
+
+            }
+            catch { }
+
+            BUT_Calibrateradio.Text = "Click when Done";
+
+            run = true;
+
+
+            while (run)
+            {
+                Application.DoEvents();
+
+                System.Threading.Thread.Sleep(5);
+
+                MainV2.cs.UpdateCurrentSettings(currentStateBindingSource, true, MainV2.comPort);
+
+                // check for non 0 values
+                if (MainV2.cs.ch1in > 800 && MainV2.cs.ch1in < 2200)
+                {
+                    rcmin[0] = Math.Min(rcmin[0], MainV2.cs.ch1in);
+                    rcmax[0] = Math.Max(rcmax[0], MainV2.cs.ch1in);
+
+                    rcmin[1] = Math.Min(rcmin[1], MainV2.cs.ch2in);
+                    rcmax[1] = Math.Max(rcmax[1], MainV2.cs.ch2in);
+
+                    rcmin[2] = Math.Min(rcmin[2], MainV2.cs.ch3in);
+                    rcmax[2] = Math.Max(rcmax[2], MainV2.cs.ch3in);
+
+                    rcmin[3] = Math.Min(rcmin[3], MainV2.cs.ch4in);
+                    rcmax[3] = Math.Max(rcmax[3], MainV2.cs.ch4in);
+
+                    rcmin[4] = Math.Min(rcmin[4], MainV2.cs.ch5in);
+                    rcmax[4] = Math.Max(rcmax[4], MainV2.cs.ch5in);
+
+                    rcmin[5] = Math.Min(rcmin[5], MainV2.cs.ch6in);
+                    rcmax[5] = Math.Max(rcmax[5], MainV2.cs.ch6in);
+
+                    rcmin[6] = Math.Min(rcmin[6], MainV2.cs.ch7in);
+                    rcmax[6] = Math.Max(rcmax[6], MainV2.cs.ch7in);
+
+                    rcmin[7] = Math.Min(rcmin[7], MainV2.cs.ch8in);
+                    rcmax[7] = Math.Max(rcmax[7], MainV2.cs.ch8in);
+
+                    BARroll.minline = (int)rcmin[0];
+                    BARroll.maxline = (int)rcmax[0];
+
+                    BARpitch.minline = (int)rcmin[1];
+                    BARpitch.maxline = (int)rcmax[1];
+
+                    BARthrottle.minline = (int)rcmin[2];
+                    BARthrottle.maxline = (int)rcmax[2];
+
+                    BARyaw.minline = (int)rcmin[3];
+                    BARyaw.maxline = (int)rcmax[3];
+
+                    BAR5.minline = (int)rcmin[4];
+                    BAR5.maxline = (int)rcmax[4];
+
+                    BAR6.minline = (int)rcmin[5];
+                    BAR6.maxline = (int)rcmax[5];
+
+                    BAR7.minline = (int)rcmin[6];
+                    BAR7.maxline = (int)rcmax[6];
+
+                    BAR8.minline = (int)rcmin[7];
+                    BAR8.maxline = (int)rcmax[7];
+
+                }
+            }
+
+            CustomMessageBox.Show("Ensure all your sticks are centered and throttle is down, and click ok to continue");
+
+            MainV2.cs.UpdateCurrentSettings(currentStateBindingSource, true, MainV2.comPort);
+
+            rctrim[0] = MainV2.cs.ch1in;
+            rctrim[1] = MainV2.cs.ch2in;
+            rctrim[2] = MainV2.cs.ch3in;
+            rctrim[3] = MainV2.cs.ch4in;
+            rctrim[4] = MainV2.cs.ch5in;
+            rctrim[5] = MainV2.cs.ch6in;
+            rctrim[6] = MainV2.cs.ch7in;
+            rctrim[7] = MainV2.cs.ch8in;
+
+            string data = "---------------\n";
+
+            for (int a = 0; a < 8; a++)
+            {
+                // we want these to save no matter what
+                BUT_Calibrateradio.Text = "Saving";
+                try
+                {
+                    if (rcmin[a] != rcmax[a])
+                    {
+                        MainV2.comPort.setParam("RC" + (a + 1).ToString("0") + "_MIN", rcmin[a]);
+                        MainV2.comPort.setParam("RC" + (a + 1).ToString("0") + "_MAX", rcmax[a]);
+                    }
+                    if (rctrim[a] < 1195 || rctrim[a] > 1205)
+                        MainV2.comPort.setParam("RC" + (a + 1).ToString("0") + "_TRIM", rctrim[a]);
+                }
+                catch { CustomMessageBox.Show("Failed to set Channel " + (a + 1).ToString()); }
+
+                data = data + "CH" + (a + 1) + " " + rcmin[a] + " | " + rcmax[a] + "\n";
+            }
+
+            MainV2.cs.raterc = oldrc;
+            MainV2.cs.rateattitude = oldatt;
+            MainV2.cs.rateposition = oldpos;
+            MainV2.cs.ratestatus = oldstatus;
+
+            try
+            {
+
+                MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RC_CHANNELS, oldrc);
+
+            }
+            catch { }
+
+            CustomMessageBox.Show("Here are the detected radio options\nNOTE Channels not connected are displayed as 1500 +-2\nNormal values are around 1100 | 1900\nChannel:Min | Max \n" + data, "Radio");
+
+            BUT_Calibrateradio.Text = "Completed";
+        }
+
+        private void CHK_mixmode_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            try
+            {
+                if (MainV2.comPort.param["ELEVON_MIXING"] == null)
+                {
+                    CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+                }
+                else
+                {
+                    MainV2.comPort.setParam("ELEVON_MIXING", ((CheckBox)sender).Checked == true ? 1 : 0);
+                }
+            }
+            catch { CustomMessageBox.Show("Set ELEVON_MIXING Failed"); }
+        }
+
+        private void CHK_elevonrev_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            try
+            {
+                if (MainV2.comPort.param["ELEVON_REVERSE"] == null)
+                {
+                    CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+                }
+                else
+                {
+                    MainV2.comPort.setParam("ELEVON_REVERSE", ((CheckBox)sender).Checked == true ? 1 : 0);
+                }
+            }
+            catch { CustomMessageBox.Show("Set ELEVON_REVERSE Failed"); }
+        }
+
+        private void CHK_elevonch1rev_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            try
+            {
+                if (MainV2.comPort.param["ELEVON_CH1_REV"] == null)
+                {
+                    CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+                }
+                else
+                {
+                    MainV2.comPort.setParam("ELEVON_CH1_REV", ((CheckBox)sender).Checked == true ? 1 : 0);
+                }
+            }
+            catch { CustomMessageBox.Show("Set ELEVON_CH1_REV Failed"); }
+        }
+
+        private void CHK_elevonch2rev_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            try
+            {
+                if (MainV2.comPort.param["ELEVON_CH2_REV"] == null)
+                {
+                    CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+                }
+                else
+                {
+                    MainV2.comPort.setParam("ELEVON_CH2_REV", ((CheckBox)sender).Checked == true ? 1 : 0);
+                }
+            }
+            catch { CustomMessageBox.Show("Set ELEVON_CH2_REV Failed"); }
+        }
+
+        private void CHK_revch1_CheckedChanged(object sender, EventArgs e)
+        {
+            reverseChannel("RC1_REV", ((CheckBox)sender).Checked, BARroll);
+        }
+
+        private void CHK_revch2_CheckedChanged(object sender, EventArgs e)
+        {
+            reverseChannel("RC2_REV", ((CheckBox)sender).Checked, BARpitch);
+        }
+
+        private void CHK_revch3_CheckedChanged(object sender, EventArgs e)
+        {
+            reverseChannel("RC3_REV", ((CheckBox)sender).Checked, BARthrottle);
+        }
+
+        private void CHK_revch4_CheckedChanged(object sender, EventArgs e)
+        {
+            reverseChannel("RC4_REV", ((CheckBox)sender).Checked, BARyaw);
+        }
+
+        void reverseChannel(string name, bool normalreverse, Control progressbar)
+        {
+            if (normalreverse == true)
+            {
+                ((HorizontalProgressBar2)progressbar).reverse = true;
+                ((HorizontalProgressBar2)progressbar).BackgroundColor = Color.FromArgb(148, 193, 31);
+                ((HorizontalProgressBar2)progressbar).ValueColor = Color.FromArgb(0x43, 0x44, 0x45);
+            }
+            else
+            {
+                ((HorizontalProgressBar2)progressbar).reverse = false;
+                ((HorizontalProgressBar2)progressbar).BackgroundColor = Color.FromArgb(0x43, 0x44, 0x45);
+                ((HorizontalProgressBar2)progressbar).ValueColor = Color.FromArgb(148, 193, 31);
+            }
+
+            if (startup)
+                return;
+            if (MainV2.comPort.param["SWITCH_ENABLE"] != null && (float)MainV2.comPort.param["SWITCH_ENABLE"] == 1)
+            {
+                try
+                {
+                    MainV2.comPort.setParam("SWITCH_ENABLE", 0);
+                    CustomMessageBox.Show("Disabled Dip Switchs");
+                }
+                catch { CustomMessageBox.Show("Error Disableing Dip Switch"); }
+            }
+            try
+            {
+                int i = normalreverse == false ? 1 : -1;
+                MainV2.comPort.setParam(name, i);
+            }
+            catch { CustomMessageBox.Show("Error Reversing"); }
+        }
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.es-ES.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.es-ES.resx
new file mode 100644
index 0000000000000000000000000000000000000000..70ad73f1af84a8cec236442b9c51462353fceab5
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.es-ES.resx
@@ -0,0 +1,315 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manual</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Modo actual:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Habilitar el flujo óptico</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>NOTA: Las imágenes son sólo para su presentación</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Actual:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APMSetup</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Swash-Servo posición</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Activar Compas</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Ajuste Chásis (+ or x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modos</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Reset</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Superior</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Swash de Viaje</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manual</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Timón de Viaje</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibración del sensor de voltaje:Para calibrar el sensor, use un multímetro para medir la tensión que sale de la CES de la batería-la eliminación del circuito (se trata de cables negro y rojo en el cable de tres hilos que suministra energía a la placa APM).Luego reste 0,3 V de ese valor y entrar en él en el campo # 1 a la izquierda.</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrar Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Modo de Vuelo 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Alabeo Max</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Modo de Vuelo 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Cabeceo Max</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>por ejemplo, en grados 2 ° 3 'W es -2,3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Modo de Vuelo 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Nivel tu quad para establecer las compensaciones por defecto acel</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Modo de Vuelo 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacidad</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Declinación</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Activar Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Entrada Radio</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibración</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Modo de Vuelo 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Modo de Vuelo 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Gyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Sitio Web Declinación</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batería</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Cero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Activar Airspeed</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Restablecer los Ajustes de hardware APM</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.fr.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.fr.resx
new file mode 100644
index 0000000000000000000000000000000000000000..1bd274beea2e052315a0ab1e83d3619dcf47cbf1
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.fr.resx
@@ -0,0 +1,312 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manuel</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Mode Courant:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Activ. capteur optique</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>NOTE: images pou presentation uniquement. Fonctionnel pour Hex, Octo etc...</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Actuel:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APMSetup</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Swash-Servo position</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Activ. Boussole</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>type de châssis (+ ou x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modes</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Réinit.</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Haut</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Mouvement Swash</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manuel</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Deplac. du Gouvernail</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibration du capteur de Voltage.1. Mesurer le voltage sur APM et inscrivez-le dans la boite ci-bas.2. Mesurer le voltage de la batterie et inscrivez-le dans la boite ci-bas.3. Inscrire les ampères par volt de la documentation du capteur de courant ci-bas</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrer Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Mode de vol 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Roulis Max</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Mode de vol 2</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Tangage Max</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>en degrés eg 2° 3' W est -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Mode de vol 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Niveler l'apareil pour copensation des accels</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Mode de vol 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacité</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Déclination</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Activer Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Entrée Radio</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Mode de vol 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Mode de vol 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Gyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Matériel</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Site Web Déclination</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batterie</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zéro</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Activ. Airspeed</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>RàZ tout parametres du APM</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Moniteur</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.it-IT.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.it-IT.resx
new file mode 100644
index 0000000000000000000000000000000000000000..2b2636c8132c76e5855c9dbb2c87151786f287c3
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.it-IT.resx
@@ -0,0 +1,318 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manuale</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Modo Corrente:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Abilita Flusso ottico</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>Nota: le immagini sono sono per presentazione, funzionerà con Hexa, etc.</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevatore CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Corrente:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>Imposta APM</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Posizione del servo del piatto</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Abilita Magnetometro</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Imposta Frame (+ or x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modi</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Riavvia</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Alto</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Escursione del piatto</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manuale</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Escursione Timone</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibarzione del sensore di voltaggio:
+1. Misura il valtaggio di ingresso di APM e inseriscilo nel box sotto 
+2. Misura il voltaggio della batteria e inseriscilo nel box sotto 
+3. Dalle caratteristiche del sensore di corrente, inserisci il valore degli ampere per volt nel box qui sotto</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrazione Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Massimo</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Modo di volo 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Rollio massimo</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Modo di volo 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Passo massimo</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>in gradi es 2° 3' W is -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Modo di volo 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Livella il quad per impostare gli accelerometri</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Modo di volo 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacità</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Declinazione</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Attiva Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Ingresso Radio</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibration</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Modo di volo 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Modo di volo 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Giroscopio</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Sito Web per la Declinazione</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batteria</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Attiva Sensore Velocità</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Resetta APM ai valori di Default</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.pl.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.pl.resx
new file mode 100644
index 0000000000000000000000000000000000000000..057b9327168c6471be22139b5d017e20582de843
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.pl.resx
@@ -0,0 +1,318 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Ręczne</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Aktualny tryb:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Włącz Optical Flow</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>UWAGA: Obrazy są wyłącznie do prezentacji, działają jedynie z hexa, itp.</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Odwr. Elevon CH1</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>Aktualny PWM:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>Ustawienia APM</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Pozycja serwa płyty ster.</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Włącz kompas</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Ustawienie ramy (+ lub x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Tryby</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Reset</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Góra</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Zakres ruchu płyty sterującej</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Ręczne</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Zakres steru kierunku</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Kalibracja czujnika napięcia:
+1. Zmierz napięcie wejściowe APM i wpisz poniżej
+2. Zmierz napięcie baterii i wpisz poniżej
+3. Wpisz poniżej ilość amperów/wolt [A/V] z dokumentacji czujnika prądu</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Kalibracja radia</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Tryb lotu 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Max przechylenie</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Tryb lotu 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Max pochylenie</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>w stopniech np. 2° 3' W to -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Tryb lotu 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Wypoziomuj quada żeby stawić domyśle offsety przysp.</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Tryb lotu 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Pojemność</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Deklinacja</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Włącz sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Wejścia radia</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibration</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Tryb lotu 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Tryb lotu 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Żyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Strona www deklinacji</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Bateria</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Włącz prędkość powietrza</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Reset APM do stawień domyślnych</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.resx
new file mode 100644
index 0000000000000000000000000000000000000000..f4c0f26f3b53c9d87c859e5fd9a61ac26872785c
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.resx
@@ -0,0 +1,606 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
+  <data name="CHK_mixmode.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
+  <data name="CHK_mixmode.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="CHK_mixmode.Location" type="System.Drawing.Point, System.Drawing">
+    <value>13, 19</value>
+  </data>
+  <data name="CHK_mixmode.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 17</value>
+  </data>
+  <data name="CHK_mixmode.TabIndex" type="System.Int32, mscorlib">
+    <value>107</value>
+  </data>
+  <data name="CHK_mixmode.Text" xml:space="preserve">
+    <value>Elevons</value>
+  </data>
+  <data name="&gt;&gt;CHK_mixmode.Name" xml:space="preserve">
+    <value>CHK_mixmode</value>
+  </data>
+  <data name="&gt;&gt;CHK_mixmode.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CHK_mixmode.Parent" xml:space="preserve">
+    <value>groupBoxElevons</value>
+  </data>
+  <data name="&gt;&gt;CHK_mixmode.ZOrder" xml:space="preserve">
+    <value>0</value>
+  </data>
+  <data name="CHK_elevonch2rev.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="CHK_elevonch2rev.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="CHK_elevonch2rev.Location" type="System.Drawing.Point, System.Drawing">
+    <value>292, 19</value>
+  </data>
+  <data name="CHK_elevonch2rev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>111, 17</value>
+  </data>
+  <data name="CHK_elevonch2rev.TabIndex" type="System.Int32, mscorlib">
+    <value>110</value>
+  </data>
+  <data name="CHK_elevonch2rev.Text" xml:space="preserve">
+    <value>Elevons CH2 Rev</value>
+  </data>
+  <data name="&gt;&gt;CHK_elevonch2rev.Name" xml:space="preserve">
+    <value>CHK_elevonch2rev</value>
+  </data>
+  <data name="&gt;&gt;CHK_elevonch2rev.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CHK_elevonch2rev.Parent" xml:space="preserve">
+    <value>groupBoxElevons</value>
+  </data>
+  <data name="&gt;&gt;CHK_elevonch2rev.ZOrder" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CHK_elevonrev.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="CHK_elevonrev.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="CHK_elevonrev.Location" type="System.Drawing.Point, System.Drawing">
+    <value>82, 19</value>
+  </data>
+  <data name="CHK_elevonrev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>87, 17</value>
+  </data>
+  <data name="CHK_elevonrev.TabIndex" type="System.Int32, mscorlib">
+    <value>108</value>
+  </data>
+  <data name="CHK_elevonrev.Text" xml:space="preserve">
+    <value>Elevons Rev</value>
+  </data>
+  <data name="&gt;&gt;CHK_elevonrev.Name" xml:space="preserve">
+    <value>CHK_elevonrev</value>
+  </data>
+  <data name="&gt;&gt;CHK_elevonrev.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CHK_elevonrev.Parent" xml:space="preserve">
+    <value>groupBoxElevons</value>
+  </data>
+  <data name="&gt;&gt;CHK_elevonrev.ZOrder" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="CHK_elevonch1rev.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="CHK_elevonch1rev.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="CHK_elevonch1rev.Location" type="System.Drawing.Point, System.Drawing">
+    <value>175, 19</value>
+  </data>
+  <data name="CHK_elevonch1rev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>111, 17</value>
+  </data>
+  <data name="CHK_elevonch1rev.TabIndex" type="System.Int32, mscorlib">
+    <value>109</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 Rev</value>
+  </data>
+  <data name="&gt;&gt;CHK_elevonch1rev.Name" xml:space="preserve">
+    <value>CHK_elevonch1rev</value>
+  </data>
+  <data name="&gt;&gt;CHK_elevonch1rev.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CHK_elevonch1rev.Parent" xml:space="preserve">
+    <value>groupBoxElevons</value>
+  </data>
+  <data name="&gt;&gt;CHK_elevonch1rev.ZOrder" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="groupBoxElevons.Location" type="System.Drawing.Point, System.Drawing">
+    <value>12, 356</value>
+  </data>
+  <data name="groupBoxElevons.Size" type="System.Drawing.Size, System.Drawing">
+    <value>409, 42</value>
+  </data>
+  <data name="groupBoxElevons.TabIndex" type="System.Int32, mscorlib">
+    <value>125</value>
+  </data>
+  <data name="groupBoxElevons.Text" xml:space="preserve">
+    <value>Elevon Config</value>
+  </data>
+  <data name="&gt;&gt;groupBoxElevons.Name" xml:space="preserve">
+    <value>groupBoxElevons</value>
+  </data>
+  <data name="&gt;&gt;groupBoxElevons.Type" xml:space="preserve">
+    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;groupBoxElevons.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;groupBoxElevons.ZOrder" xml:space="preserve">
+    <value>0</value>
+  </data>
+  <data name="CHK_revch3.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="CHK_revch3.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="CHK_revch3.Location" type="System.Drawing.Point, System.Drawing">
+    <value>278, 161</value>
+  </data>
+  <data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>66, 17</value>
+  </data>
+  <data name="CHK_revch3.TabIndex" type="System.Int32, mscorlib">
+    <value>124</value>
+  </data>
+  <data name="CHK_revch3.Text" xml:space="preserve">
+    <value>Reverse</value>
+  </data>
+  <data name="&gt;&gt;CHK_revch3.Name" xml:space="preserve">
+    <value>CHK_revch3</value>
+  </data>
+  <data name="&gt;&gt;CHK_revch3.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CHK_revch3.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CHK_revch3.ZOrder" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CHK_revch4.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="CHK_revch4.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="CHK_revch4.Location" type="System.Drawing.Point, System.Drawing">
+    <value>306, 313</value>
+  </data>
+  <data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>66, 17</value>
+  </data>
+  <data name="CHK_revch4.TabIndex" type="System.Int32, mscorlib">
+    <value>123</value>
+  </data>
+  <data name="CHK_revch4.Text" xml:space="preserve">
+    <value>Reverse</value>
+  </data>
+  <data name="&gt;&gt;CHK_revch4.Name" xml:space="preserve">
+    <value>CHK_revch4</value>
+  </data>
+  <data name="&gt;&gt;CHK_revch4.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CHK_revch4.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CHK_revch4.ZOrder" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="CHK_revch2.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="CHK_revch2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="CHK_revch2.Location" type="System.Drawing.Point, System.Drawing">
+    <value>62, 161</value>
+  </data>
+  <data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>66, 17</value>
+  </data>
+  <data name="CHK_revch2.TabIndex" type="System.Int32, mscorlib">
+    <value>122</value>
+  </data>
+  <data name="CHK_revch2.Text" xml:space="preserve">
+    <value>Reverse</value>
+  </data>
+  <data name="&gt;&gt;CHK_revch2.Name" xml:space="preserve">
+    <value>CHK_revch2</value>
+  </data>
+  <data name="&gt;&gt;CHK_revch2.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CHK_revch2.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CHK_revch2.ZOrder" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="CHK_revch1.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="CHK_revch1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="CHK_revch1.Location" type="System.Drawing.Point, System.Drawing">
+    <value>306, 19</value>
+  </data>
+  <data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>66, 17</value>
+  </data>
+  <data name="CHK_revch1.TabIndex" type="System.Int32, mscorlib">
+    <value>121</value>
+  </data>
+  <data name="CHK_revch1.Text" xml:space="preserve">
+    <value>Reverse</value>
+  </data>
+  <data name="&gt;&gt;CHK_revch1.Name" xml:space="preserve">
+    <value>CHK_revch1</value>
+  </data>
+  <data name="&gt;&gt;CHK_revch1.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CHK_revch1.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;CHK_revch1.ZOrder" xml:space="preserve">
+    <value>4</value>
+  </data>
+  <data name="BUT_Calibrateradio.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="BUT_Calibrateradio.Location" type="System.Drawing.Point, System.Drawing">
+    <value>473, 347</value>
+  </data>
+  <data name="BUT_Calibrateradio.Size" type="System.Drawing.Size, System.Drawing">
+    <value>134, 23</value>
+  </data>
+  <data name="BUT_Calibrateradio.TabIndex" type="System.Int32, mscorlib">
+    <value>120</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrate Radio</value>
+  </data>
+  <data name="&gt;&gt;BUT_Calibrateradio.Name" xml:space="preserve">
+    <value>BUT_Calibrateradio</value>
+  </data>
+  <data name="&gt;&gt;BUT_Calibrateradio.Type" xml:space="preserve">
+    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;BUT_Calibrateradio.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;BUT_Calibrateradio.ZOrder" xml:space="preserve">
+    <value>5</value>
+  </data>
+  <metadata name="currentStateBindingSource.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
+    <value>17, 17</value>
+  </metadata>
+  <data name="BAR8.Location" type="System.Drawing.Point, System.Drawing">
+    <value>437, 247</value>
+  </data>
+  <data name="BAR8.Size" type="System.Drawing.Size, System.Drawing">
+    <value>170, 25</value>
+  </data>
+  <data name="BAR8.TabIndex" type="System.Int32, mscorlib">
+    <value>119</value>
+  </data>
+  <data name="&gt;&gt;BAR8.Name" xml:space="preserve">
+    <value>BAR8</value>
+  </data>
+  <data name="&gt;&gt;BAR8.Type" xml:space="preserve">
+    <value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;BAR8.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;BAR8.ZOrder" xml:space="preserve">
+    <value>6</value>
+  </data>
+  <data name="BAR7.Location" type="System.Drawing.Point, System.Drawing">
+    <value>437, 192</value>
+  </data>
+  <data name="BAR7.Size" type="System.Drawing.Size, System.Drawing">
+    <value>170, 25</value>
+  </data>
+  <data name="BAR7.TabIndex" type="System.Int32, mscorlib">
+    <value>118</value>
+  </data>
+  <data name="&gt;&gt;BAR7.Name" xml:space="preserve">
+    <value>BAR7</value>
+  </data>
+  <data name="&gt;&gt;BAR7.Type" xml:space="preserve">
+    <value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;BAR7.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;BAR7.ZOrder" xml:space="preserve">
+    <value>7</value>
+  </data>
+  <data name="BAR6.Location" type="System.Drawing.Point, System.Drawing">
+    <value>437, 137</value>
+  </data>
+  <data name="BAR6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>170, 25</value>
+  </data>
+  <data name="BAR6.TabIndex" type="System.Int32, mscorlib">
+    <value>117</value>
+  </data>
+  <data name="&gt;&gt;BAR6.Name" xml:space="preserve">
+    <value>BAR6</value>
+  </data>
+  <data name="&gt;&gt;BAR6.Type" xml:space="preserve">
+    <value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;BAR6.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;BAR6.ZOrder" xml:space="preserve">
+    <value>8</value>
+  </data>
+  <data name="BAR5.Location" type="System.Drawing.Point, System.Drawing">
+    <value>437, 82</value>
+  </data>
+  <data name="BAR5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>170, 25</value>
+  </data>
+  <data name="BAR5.TabIndex" type="System.Int32, mscorlib">
+    <value>116</value>
+  </data>
+  <data name="&gt;&gt;BAR5.Name" xml:space="preserve">
+    <value>BAR5</value>
+  </data>
+  <data name="&gt;&gt;BAR5.Type" xml:space="preserve">
+    <value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;BAR5.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;BAR5.ZOrder" xml:space="preserve">
+    <value>9</value>
+  </data>
+  <data name="BARpitch.Location" type="System.Drawing.Point, System.Drawing">
+    <value>134, 64</value>
+  </data>
+  <data name="BARpitch.Size" type="System.Drawing.Size, System.Drawing">
+    <value>47, 211</value>
+  </data>
+  <data name="BARpitch.TabIndex" type="System.Int32, mscorlib">
+    <value>115</value>
+  </data>
+  <data name="&gt;&gt;BARpitch.Name" xml:space="preserve">
+    <value>BARpitch</value>
+  </data>
+  <data name="&gt;&gt;BARpitch.Type" xml:space="preserve">
+    <value>ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;BARpitch.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;BARpitch.ZOrder" xml:space="preserve">
+    <value>10</value>
+  </data>
+  <data name="BARthrottle.Location" type="System.Drawing.Point, System.Drawing">
+    <value>350, 64</value>
+  </data>
+  <data name="BARthrottle.Size" type="System.Drawing.Size, System.Drawing">
+    <value>47, 211</value>
+  </data>
+  <data name="BARthrottle.TabIndex" type="System.Int32, mscorlib">
+    <value>114</value>
+  </data>
+  <data name="&gt;&gt;BARthrottle.Name" xml:space="preserve">
+    <value>BARthrottle</value>
+  </data>
+  <data name="&gt;&gt;BARthrottle.Type" xml:space="preserve">
+    <value>ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;BARthrottle.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;BARthrottle.ZOrder" xml:space="preserve">
+    <value>11</value>
+  </data>
+  <data name="BARyaw.Location" type="System.Drawing.Point, System.Drawing">
+    <value>12, 307</value>
+  </data>
+  <data name="BARyaw.Size" type="System.Drawing.Size, System.Drawing">
+    <value>288, 23</value>
+  </data>
+  <data name="BARyaw.TabIndex" type="System.Int32, mscorlib">
+    <value>113</value>
+  </data>
+  <data name="&gt;&gt;BARyaw.Name" xml:space="preserve">
+    <value>BARyaw</value>
+  </data>
+  <data name="&gt;&gt;BARyaw.Type" xml:space="preserve">
+    <value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;BARyaw.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;BARyaw.ZOrder" xml:space="preserve">
+    <value>12</value>
+  </data>
+  <data name="BARroll.Location" type="System.Drawing.Point, System.Drawing">
+    <value>12, 13</value>
+  </data>
+  <data name="BARroll.Size" type="System.Drawing.Size, System.Drawing">
+    <value>288, 23</value>
+  </data>
+  <data name="BARroll.TabIndex" type="System.Int32, mscorlib">
+    <value>112</value>
+  </data>
+  <data name="&gt;&gt;BARroll.Name" xml:space="preserve">
+    <value>BARroll</value>
+  </data>
+  <data name="&gt;&gt;BARroll.Type" xml:space="preserve">
+    <value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;BARroll.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;BARroll.ZOrder" xml:space="preserve">
+    <value>13</value>
+  </data>
+  <metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
+    <value>True</value>
+  </metadata>
+  <data name="$this.AutoScaleDimensions" type="System.Drawing.SizeF, System.Drawing">
+    <value>6, 13</value>
+  </data>
+  <data name="$this.Size" type="System.Drawing.Size, System.Drawing">
+    <value>628, 406</value>
+  </data>
+  <data name="&gt;&gt;currentStateBindingSource.Name" xml:space="preserve">
+    <value>currentStateBindingSource</value>
+  </data>
+  <data name="&gt;&gt;currentStateBindingSource.Type" xml:space="preserve">
+    <value>System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;$this.Name" xml:space="preserve">
+    <value>ConfigRadioInput</value>
+  </data>
+  <data name="&gt;&gt;$this.Type" xml:space="preserve">
+    <value>System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.zh-Hans.resx
new file mode 100644
index 0000000000000000000000000000000000000000..f96892c423b112b28127ad582686f33464b57c5b
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.zh-Hans.resx
@@ -0,0 +1,496 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>遥控输入</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>模式</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>硬件</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>电池</value>
+  </data>
+  <data name="tabHeli.Text" xml:space="preserve">
+    <value>AC2 直升机</value>
+  </data>
+  <data name="groupBoxElevons.Text" xml:space="preserve">
+    <value>上降副翼 (Elevon) 配置</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="CHK_elevonch2rev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>115, 17</value>
+  </data>
+  <data name="CHK_elevonch2rev.Text" xml:space="preserve">
+    <value>Elevons CH2 逆转</value>
+  </data>
+  <data name="CHK_elevonrev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>91, 17</value>
+  </data>
+  <data name="CHK_elevonrev.Text" xml:space="preserve">
+    <value>Elevons 逆转</value>
+  </data>
+  <data name="CHK_elevonch1rev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>115, 17</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 逆转</value>
+  </data>
+  <data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch3.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch4.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch2.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch1.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>校准遥控</value>
+  </data>
+  <data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="label14.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>当前 PWM:</value>
+  </data>
+  <data name="label13.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>当前模式:</value>
+  </data>
+  <data name="label6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>飞行模式 6</value>
+  </data>
+  <data name="label5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>飞行模式 5</value>
+  </data>
+  <data name="label4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>飞行模式 4</value>
+  </data>
+  <data name="label3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>飞行模式 3</value>
+  </data>
+  <data name="label2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>飞行模式 2</value>
+  </data>
+  <data name="label1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>飞行模式 1</value>
+  </data>
+  <data name="BUT_SaveModes.Text" xml:space="preserve">
+    <value>保存模式</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>十进制, 2° 3' W 就是 -2.3</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>启用光流</value>
+  </data>
+  <data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
+    <value>67, 13</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>磁偏角网站</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>磁偏角</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>启用空速计</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>启用声纳</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>启用罗盘</value>
+  </data>
+  <data name="label31.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label31.Text" xml:space="preserve">
+    <value>输入电压:</value>
+  </data>
+  <data name="label32.Size" type="System.Drawing.Size, System.Drawing">
+    <value>94, 13</value>
+  </data>
+  <data name="label32.Text" xml:space="preserve">
+    <value>测量的电池电压:</value>
+  </data>
+  <data name="label33.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label33.Text" xml:space="preserve">
+    <value>电池电压:</value>
+  </data>
+  <data name="label34.Size" type="System.Drawing.Size, System.Drawing">
+    <value>52, 13</value>
+  </data>
+  <data name="label34.Text" xml:space="preserve">
+    <value>分 压 比:</value>
+  </data>
+  <data name="label35.Size" type="System.Drawing.Size, System.Drawing">
+    <value>63, 13</value>
+  </data>
+  <data name="label35.Text" xml:space="preserve">
+    <value>安培/伏特:</value>
+  </data>
+  <data name="label47.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 18</value>
+  </data>
+  <data name="label47.Text" xml:space="preserve">
+    <value>传感器</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>电压传感器校准:
+1. 测量APM输入电压,输入到下方的文本框中
+2. 测量电池电压,输入到下方的文本框中
+3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中</value>
+  </data>
+  <data name="label29.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>容量</value>
+  </data>
+  <data name="label30.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 13</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>监控器</value>
+  </data>
+  <data name="label28.Size" type="System.Drawing.Size, System.Drawing">
+    <value>175, 13</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>设置水平面的默认加速度计偏移</value>
+  </data>
+  <data name="label16.Size" type="System.Drawing.Size, System.Drawing">
+    <value>261, 13</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>注: 图片只是用于展示,设置可以用于六轴等机架</value>
+  </data>
+  <data name="label15.Size" type="System.Drawing.Size, System.Drawing">
+    <value>93, 13</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>机架设置 (+ 或 x)</value>
+  </data>
+  <data name="BUT_levelac2.Text" xml:space="preserve">
+    <value>找平</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>手动</value>
+  </data>
+  <data name="BUT_swash_manual.Text" xml:space="preserve">
+    <value>手动</value>
+  </data>
+  <data name="label46.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label46.Text" xml:space="preserve">
+    <value>感度</value>
+  </data>
+  <data name="label45.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label45.Text" xml:space="preserve">
+    <value>启用</value>
+  </data>
+  <data name="label44.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label44.Text" xml:space="preserve">
+    <value>微调</value>
+  </data>
+  <data name="label43.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label43.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="label42.Size" type="System.Drawing.Size, System.Drawing">
+    <value>43, 13</value>
+  </data>
+  <data name="label42.Text" xml:space="preserve">
+    <value>方向舵</value>
+  </data>
+  <data name="label24.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>最大</value>
+  </data>
+  <data name="label40.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label40.Text" xml:space="preserve">
+    <value>最小</value>
+  </data>
+  <data name="label41.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label41.Text" xml:space="preserve">
+    <value>最低</value>
+  </data>
+  <data name="label21.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>最高</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>0度</value>
+  </data>
+  <data name="label39.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label39.Text" xml:space="preserve">
+    <value>微调</value>
+  </data>
+  <data name="label38.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label38.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="label37.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label37.Text" xml:space="preserve">
+    <value>位置</value>
+  </data>
+  <data name="label36.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label36.Text" xml:space="preserve">
+    <value>舵机</value>
+  </data>
+  <data name="label26.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>最大俯仰</value>
+  </data>
+  <data name="label25.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>最大侧倾</value>
+  </data>
+  <data name="label23.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>舵机行程</value>
+  </data>
+  <data name="label22.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>斜盘水平微调</value>
+  </data>
+  <data name="label17.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>斜盘舵机位置</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>重置</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>重置 APM 为默认设置</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APM设置</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.zh-TW.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.zh-TW.resx
new file mode 100644
index 0000000000000000000000000000000000000000..0c03fbf8ed6bd5befc34246175bf1adf106cce43
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.zh-TW.resx
@@ -0,0 +1,460 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>重置</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>遙控輸入</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>模式</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>硬件</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>電池</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>重置 APM 為默認設置</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch3.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch4.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch2.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch1.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>校準遙控</value>
+  </data>
+  <data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="label14.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>當前 PWM:</value>
+  </data>
+  <data name="label13.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>當前模式:</value>
+  </data>
+  <data name="label6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>飛行模式 6</value>
+  </data>
+  <data name="label5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>飛行模式 5</value>
+  </data>
+  <data name="label4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>飛行模式 4</value>
+  </data>
+  <data name="label3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>飛行模式 3</value>
+  </data>
+  <data name="label2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>飛行模式 2</value>
+  </data>
+  <data name="label1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>飛行模式 1</value>
+  </data>
+  <data name="BUT_SaveModes.Text" xml:space="preserve">
+    <value>保存模式</value>
+  </data>
+  <data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
+    <value>67, 13</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>磁偏角網站</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>磁偏角</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>啟用空速計</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>啟用聲納</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>啟用羅盤</value>
+  </data>
+  <data name="label35.Size" type="System.Drawing.Size, System.Drawing">
+    <value>63, 13</value>
+  </data>
+  <data name="label35.Text" xml:space="preserve">
+    <value>安培/伏特:</value>
+  </data>
+  <data name="label34.Size" type="System.Drawing.Size, System.Drawing">
+    <value>52, 13</value>
+  </data>
+  <data name="label34.Text" xml:space="preserve">
+    <value>分 壓 比:</value>
+  </data>
+  <data name="label33.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label33.Text" xml:space="preserve">
+    <value>電池電壓:</value>
+  </data>
+  <data name="label32.Size" type="System.Drawing.Size, System.Drawing">
+    <value>94, 13</value>
+  </data>
+  <data name="label32.Text" xml:space="preserve">
+    <value>測量的電池電壓:</value>
+  </data>
+  <data name="label31.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label31.Text" xml:space="preserve">
+    <value>輸入電壓:</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>電壓傳感器校準:
+1. 測量APM輸入電壓,輸入到下方的文本框中
+2. 測量電池電壓,輸入到下方的文本框中
+3. 從當前的傳感器的數據表中找到安培/伏特,輸入到下方的文本框中</value>
+  </data>
+  <data name="label29.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>容量</value>
+  </data>
+  <data name="label30.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 13</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>監控器</value>
+  </data>
+  <data name="label28.Size" type="System.Drawing.Size, System.Drawing">
+    <value>175, 13</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>設置水平面的默認加速度計偏移</value>
+  </data>
+  <data name="label16.Size" type="System.Drawing.Size, System.Drawing">
+    <value>261, 13</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>注: 圖片只是用於展示,設置可以用於六軸等機架</value>
+  </data>
+  <data name="label15.Size" type="System.Drawing.Size, System.Drawing">
+    <value>93, 13</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>機架設置 (+ 或 x)</value>
+  </data>
+  <data name="BUT_levelac2.Text" xml:space="preserve">
+    <value>找平</value>
+  </data>
+  <data name="label46.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label46.Text" xml:space="preserve">
+    <value>感度</value>
+  </data>
+  <data name="label45.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label45.Text" xml:space="preserve">
+    <value>啟用</value>
+  </data>
+  <data name="label44.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label44.Text" xml:space="preserve">
+    <value>微調</value>
+  </data>
+  <data name="label43.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label43.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="label42.Size" type="System.Drawing.Size, System.Drawing">
+    <value>43, 13</value>
+  </data>
+  <data name="label42.Text" xml:space="preserve">
+    <value>方向舵</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>手動</value>
+  </data>
+  <data name="label24.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>最大</value>
+  </data>
+  <data name="label40.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label40.Text" xml:space="preserve">
+    <value>最小</value>
+  </data>
+  <data name="BUT_swash_manual.Text" xml:space="preserve">
+    <value>手動</value>
+  </data>
+  <data name="label41.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label41.Text" xml:space="preserve">
+    <value>最低</value>
+  </data>
+  <data name="label21.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>最高</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>0度</value>
+  </data>
+  <data name="label39.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label39.Text" xml:space="preserve">
+    <value>微調</value>
+  </data>
+  <data name="label38.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label38.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="label37.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label37.Text" xml:space="preserve">
+    <value>位置</value>
+  </data>
+  <data name="label36.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label36.Text" xml:space="preserve">
+    <value>舵機</value>
+  </data>
+  <data name="label26.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>最大俯仰</value>
+  </data>
+  <data name="label25.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>最大側傾</value>
+  </data>
+  <data name="label23.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>舵機行程</value>
+  </data>
+  <data name="label22.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>斜盤水平微調</value>
+  </data>
+  <data name="label17.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>斜盤舵機位置</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APM設置</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs
new file mode 100644
index 0000000000000000000000000000000000000000..8ef9695b9248d63afad52b09590e2dfdd48936f8
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs
@@ -0,0 +1,213 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    partial class ConfigRawParams
+    {
+        /// <summary> 
+        /// Required designer variable.
+        /// </summary>
+        private System.ComponentModel.IContainer components = null;
+
+        /// <summary> 
+        /// Clean up any resources being used.
+        /// </summary>
+        /// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
+        protected override void Dispose(bool disposing)
+        {
+            if (disposing && (components != null))
+            {
+                components.Dispose();
+            }
+            base.Dispose(disposing);
+        }
+
+        #region Component Designer generated code
+
+        /// <summary> 
+        /// Required method for Designer support - do not modify 
+        /// the contents of this method with the code editor.
+        /// </summary>
+        private void InitializeComponent()
+        {
+            this.components = new System.ComponentModel.Container();
+            System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle();
+            System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle();
+            this.BUT_compare = new ArdupilotMega.MyButton();
+            this.BUT_rerequestparams = new ArdupilotMega.MyButton();
+            this.BUT_writePIDS = new ArdupilotMega.MyButton();
+            this.BUT_save = new ArdupilotMega.MyButton();
+            this.BUT_load = new ArdupilotMega.MyButton();
+            this.Params = new System.Windows.Forms.DataGridView();
+            this.Command = new System.Windows.Forms.DataGridViewTextBoxColumn();
+            this.Value = new System.Windows.Forms.DataGridViewTextBoxColumn();
+            this.Default = new System.Windows.Forms.DataGridViewTextBoxColumn();
+            this.mavScale = new System.Windows.Forms.DataGridViewTextBoxColumn();
+            this.RawValue = new System.Windows.Forms.DataGridViewTextBoxColumn();
+            this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
+            ((System.ComponentModel.ISupportInitialize)(this.Params)).BeginInit();
+            this.SuspendLayout();
+            // 
+            // BUT_compare
+            // 
+            this.BUT_compare.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Right)));
+            this.BUT_compare.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.BUT_compare.Location = new System.Drawing.Point(341, 119);
+            this.BUT_compare.Name = "BUT_compare";
+            this.BUT_compare.Size = new System.Drawing.Size(103, 19);
+            this.BUT_compare.TabIndex = 72;
+            this.BUT_compare.Text = "Compare Params";
+            this.BUT_compare.UseVisualStyleBackColor = true;
+            this.BUT_compare.Click += new System.EventHandler(this.BUT_compare_Click);
+            // 
+            // BUT_rerequestparams
+            // 
+            this.BUT_rerequestparams.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Right)));
+            this.BUT_rerequestparams.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.BUT_rerequestparams.Location = new System.Drawing.Point(341, 94);
+            this.BUT_rerequestparams.Name = "BUT_rerequestparams";
+            this.BUT_rerequestparams.Size = new System.Drawing.Size(103, 19);
+            this.BUT_rerequestparams.TabIndex = 67;
+            this.BUT_rerequestparams.Text = "Refresh Params";
+            this.BUT_rerequestparams.UseVisualStyleBackColor = true;
+            this.BUT_rerequestparams.Click += new System.EventHandler(this.BUT_rerequestparams_Click);
+            // 
+            // BUT_writePIDS
+            // 
+            this.BUT_writePIDS.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Right)));
+            this.BUT_writePIDS.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.BUT_writePIDS.Location = new System.Drawing.Point(341, 69);
+            this.BUT_writePIDS.Name = "BUT_writePIDS";
+            this.BUT_writePIDS.Size = new System.Drawing.Size(103, 19);
+            this.BUT_writePIDS.TabIndex = 69;
+            this.BUT_writePIDS.Text = "Write Params";
+            this.BUT_writePIDS.UseVisualStyleBackColor = true;
+            this.BUT_writePIDS.Click += new System.EventHandler(this.BUT_writePIDS_Click);
+            // 
+            // BUT_save
+            // 
+            this.BUT_save.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Right)));
+            this.BUT_save.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.BUT_save.Location = new System.Drawing.Point(341, 35);
+            this.BUT_save.Margin = new System.Windows.Forms.Padding(0);
+            this.BUT_save.Name = "BUT_save";
+            this.BUT_save.Size = new System.Drawing.Size(104, 19);
+            this.BUT_save.TabIndex = 70;
+            this.BUT_save.Text = "Save";
+            this.BUT_save.UseVisualStyleBackColor = true;
+            this.BUT_save.Click += new System.EventHandler(this.BUT_save_Click);
+            // 
+            // BUT_load
+            // 
+            this.BUT_load.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Right)));
+            this.BUT_load.ImeMode = System.Windows.Forms.ImeMode.NoControl;
+            this.BUT_load.Location = new System.Drawing.Point(341, 7);
+            this.BUT_load.Margin = new System.Windows.Forms.Padding(0);
+            this.BUT_load.Name = "BUT_load";
+            this.BUT_load.Size = new System.Drawing.Size(104, 19);
+            this.BUT_load.TabIndex = 71;
+            this.BUT_load.Text = "Load";
+            this.BUT_load.UseVisualStyleBackColor = true;
+            this.BUT_load.Click += new System.EventHandler(this.BUT_load_Click);
+            // 
+            // Params
+            // 
+            this.Params.AllowUserToAddRows = false;
+            this.Params.AllowUserToDeleteRows = false;
+            this.Params.Anchor = ((System.Windows.Forms.AnchorStyles)((((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Bottom) 
+            | System.Windows.Forms.AnchorStyles.Left) 
+            | System.Windows.Forms.AnchorStyles.Right)));
+            dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
+            dataGridViewCellStyle1.BackColor = System.Drawing.Color.Maroon;
+            dataGridViewCellStyle1.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
+            dataGridViewCellStyle1.ForeColor = System.Drawing.Color.White;
+            dataGridViewCellStyle1.SelectionBackColor = System.Drawing.SystemColors.Highlight;
+            dataGridViewCellStyle1.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
+            dataGridViewCellStyle1.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
+            this.Params.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle1;
+            this.Params.ColumnHeadersHeightSizeMode = System.Windows.Forms.DataGridViewColumnHeadersHeightSizeMode.AutoSize;
+            this.Params.Columns.AddRange(new System.Windows.Forms.DataGridViewColumn[] {
+            this.Command,
+            this.Value,
+            this.Default,
+            this.mavScale,
+            this.RawValue});
+            this.Params.Location = new System.Drawing.Point(14, 3);
+            this.Params.Name = "Params";
+            dataGridViewCellStyle2.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
+            dataGridViewCellStyle2.BackColor = System.Drawing.SystemColors.ActiveCaption;
+            dataGridViewCellStyle2.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
+            dataGridViewCellStyle2.ForeColor = System.Drawing.SystemColors.WindowText;
+            dataGridViewCellStyle2.SelectionBackColor = System.Drawing.SystemColors.Highlight;
+            dataGridViewCellStyle2.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
+            dataGridViewCellStyle2.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
+            this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle2;
+            this.Params.RowHeadersVisible = false;
+            this.Params.RowHeadersWidth = 150;
+            this.Params.Size = new System.Drawing.Size(321, 302);
+            this.Params.TabIndex = 68;
+            this.Params.CellValueChanged += new System.Windows.Forms.DataGridViewCellEventHandler(this.Params_CellValueChanged);
+            // 
+            // Command
+            // 
+            this.Command.HeaderText = "Command";
+            this.Command.Name = "Command";
+            this.Command.ReadOnly = true;
+            this.Command.Width = 150;
+            // 
+            // Value
+            // 
+            this.Value.HeaderText = "Value";
+            this.Value.Name = "Value";
+            this.Value.Width = 80;
+            // 
+            // Default
+            // 
+            this.Default.HeaderText = "Default";
+            this.Default.Name = "Default";
+            this.Default.Visible = false;
+            // 
+            // mavScale
+            // 
+            this.mavScale.HeaderText = "mavScale";
+            this.mavScale.Name = "mavScale";
+            this.mavScale.Visible = false;
+            // 
+            // RawValue
+            // 
+            this.RawValue.HeaderText = "RawValue";
+            this.RawValue.Name = "RawValue";
+            this.RawValue.Visible = false;
+            // 
+            // ConfigRawParams
+            // 
+            this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
+            this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+            this.Controls.Add(this.BUT_compare);
+            this.Controls.Add(this.BUT_rerequestparams);
+            this.Controls.Add(this.BUT_writePIDS);
+            this.Controls.Add(this.BUT_save);
+            this.Controls.Add(this.BUT_load);
+            this.Controls.Add(this.Params);
+            this.Name = "ConfigRawParams";
+            this.Size = new System.Drawing.Size(460, 305);
+            this.Load += new System.EventHandler(this.ConfigRawParams_Load);
+            ((System.ComponentModel.ISupportInitialize)(this.Params)).EndInit();
+            this.ResumeLayout(false);
+
+        }
+
+        #endregion
+
+        private MyButton BUT_compare;
+        private MyButton BUT_rerequestparams;
+        private MyButton BUT_writePIDS;
+        private MyButton BUT_save;
+        private MyButton BUT_load;
+        private System.Windows.Forms.DataGridView Params;
+        private System.Windows.Forms.DataGridViewTextBoxColumn Command;
+        private System.Windows.Forms.DataGridViewTextBoxColumn Value;
+        private System.Windows.Forms.DataGridViewTextBoxColumn Default;
+        private System.Windows.Forms.DataGridViewTextBoxColumn mavScale;
+        private System.Windows.Forms.DataGridViewTextBoxColumn RawValue;
+        private System.Windows.Forms.ToolTip toolTip1;
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs
new file mode 100644
index 0000000000000000000000000000000000000000..4d9cf61ece2b4aafff0f998dfab362d85ce139e1
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs
@@ -0,0 +1,429 @@
+using System;
+using System.Collections;
+using System.Collections.Generic;
+using System.ComponentModel;
+using System.Drawing;
+using System.Data;
+using System.IO;
+using System.Linq;
+using System.Text;
+using System.Windows.Forms;
+using log4net;
+using ArdupilotMega.Controls.BackstageView;
+
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    public partial class ConfigRawParams : BackStageViewContentPanel
+    {
+        private static readonly ILog log =
+          LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
+
+        // Changes made to the params between writing to the copter
+        readonly Hashtable _changes = new Hashtable();
+
+        static Hashtable tooltips = new Hashtable();
+
+        // ?
+        internal bool startup = true;
+
+        public struct paramsettings // hk's
+        {
+            public string name;
+            public float minvalue;
+            public float maxvalue;
+            public float normalvalue;
+            public float scale;
+            public string desc;
+        }
+
+
+        public ConfigRawParams()
+        {
+            InitializeComponent();
+        }
+
+        Hashtable loadParamFile(string Filename)
+        {
+            Hashtable param = new Hashtable();
+
+            StreamReader sr = new StreamReader(Filename);
+            while (!sr.EndOfStream)
+            {
+                string line = sr.ReadLine();
+
+                if (line.Contains("NOTE:"))
+                    CustomMessageBox.Show(line, "Saved Note");
+
+                if (line.StartsWith("#"))
+                    continue;
+
+                string[] items = line.Split(new char[] { ' ', ',', '\t' }, StringSplitOptions.RemoveEmptyEntries);
+
+                if (items.Length != 2)
+                    continue;
+
+                string name = items[0];
+                float value = float.Parse(items[1], new System.Globalization.CultureInfo("en-US"));
+
+                MAVLink.modifyParamForDisplay(true, name, ref value);
+
+                if (name == "SYSID_SW_MREV")
+                    continue;
+                if (name == "WP_TOTAL")
+                    continue;
+                if (name == "CMD_TOTAL")
+                    continue;
+                if (name == "FENCE_TOTAL")
+                    continue;
+                if (name == "SYS_NUM_RESETS")
+                    continue;
+                if (name == "ARSPD_OFFSET")
+                    continue;
+                if (name == "GND_ABS_PRESS")
+                    continue;
+                if (name == "GND_TEMP")
+                    continue;
+                if (name == "CMD_INDEX")
+                    continue;
+                if (name == "LOG_LASTFILE")
+                    continue;
+
+                param[name] = value;
+            }
+            sr.Close();
+
+            return param;
+        }
+
+        private void BUT_load_Click(object sender, EventArgs e)
+        {
+            var ofd = new OpenFileDialog
+                          {
+                              AddExtension = true,
+                              DefaultExt = ".param",
+                              RestoreDirectory = true,
+                              Filter = "Param List|*.param;*.parm"
+                          };
+            var dr = ofd.ShowDialog();
+
+            if (dr == DialogResult.OK)
+            {
+                Hashtable param2 = loadParamFile(ofd.FileName);
+
+                foreach (string name in param2.Keys)
+                {
+                    string value = param2[name].ToString();
+                    // set param table as well
+                    foreach (DataGridViewRow row in Params.Rows)
+                    {
+                        if (name == "SYSID_SW_MREV")
+                            continue;
+                        if (name == "WP_TOTAL")
+                            continue;
+                        if (name == "CMD_TOTAL")
+                            continue;
+                        if (name == "FENCE_TOTAL")
+                            continue;
+                        if (name == "SYS_NUM_RESETS")
+                            continue;
+                        if (name == "ARSPD_OFFSET")
+                            continue;
+                        if (name == "GND_ABS_PRESS")
+                            continue;
+                        if (name == "GND_TEMP")
+                            continue;
+                        if (name == "CMD_INDEX")
+                            continue;
+                        if (name == "LOG_LASTFILE")
+                            continue;
+                        if (row.Cells[0].Value.ToString() == name)
+                        {
+                            if (row.Cells[1].Value.ToString() != value.ToString())
+                                row.Cells[1].Value = value;
+                            break;
+                        }
+                    }
+                }
+            }
+        }
+
+        private void BUT_save_Click(object sender, EventArgs e)
+        {
+            var sfd = new SaveFileDialog
+                          {
+                              AddExtension = true,
+                              DefaultExt = ".param",
+                              RestoreDirectory = true,
+                              Filter = "Param List|*.param;*.parm"
+                          };
+
+            var dr = sfd.ShowDialog();
+            if (dr == DialogResult.OK)
+            {
+                StreamWriter sw = new StreamWriter(sfd.OpenFile());
+                string input = DateTime.Now + " Frame : + | Arducopter Kit | Kit motors";
+                if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
+                {
+                    input = DateTime.Now + " Plane: Skywalker";
+                }
+                Common.InputBox("Custom Note", "Enter your Notes/Frame Type etc", ref input);
+                if (input != "")
+                    sw.WriteLine("NOTE: " + input.Replace(',', '|'));
+                foreach (DataGridViewRow row in Params.Rows)
+                {
+                    float value = float.Parse(row.Cells[1].Value.ToString());
+
+                    MAVLink.modifyParamForDisplay(false, row.Cells[0].Value.ToString(), ref value);
+
+                    sw.WriteLine(row.Cells[0].Value.ToString() + "," + value.ToString(new System.Globalization.CultureInfo("en-US")));
+                }
+                sw.Close();
+            }
+        }
+
+        private void BUT_writePIDS_Click(object sender, EventArgs e)
+        {
+            var temp = (Hashtable)_changes.Clone();
+
+            foreach (string value in temp.Keys)
+            {
+                try
+                {
+                    MainV2.comPort.setParam(value, (float)_changes[value]);
+
+                    try
+                    {
+                        // set control as well
+                        var textControls = this.Controls.Find(value, true);
+                        if (textControls.Length > 0)
+                        {
+                            textControls[0].BackColor = Color.FromArgb(0x43, 0x44, 0x45);
+                        }
+                    }
+                    catch
+                    {
+                        
+                    }
+
+                    try
+                    {
+                        // set param table as well
+                        foreach (DataGridViewRow row in Params.Rows)
+                        {
+                            if (row.Cells[0].Value.ToString() == value)
+                            {
+                                row.Cells[1].Style.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
+                                _changes.Remove(value);
+                                break;
+                            }
+                        }
+                    }
+                    catch { }
+
+                }
+                catch
+                {
+                    CustomMessageBox.Show("Set " + value + " Failed");
+                }
+            }
+        }
+
+
+        private void BUT_compare_Click(object sender, EventArgs e)
+        {
+            Hashtable param2 = new Hashtable();
+
+            var ofd = new OpenFileDialog
+                          {
+                              AddExtension = true,
+                              DefaultExt = ".param",
+                              RestoreDirectory = true,
+                              Filter = "Param List|*.param;*.parm"
+                          };
+
+            var dr = ofd.ShowDialog();
+            if (dr == DialogResult.OK)
+            {
+                param2 = loadParamFile(ofd.FileName);
+
+                Form paramCompareForm = new ParamCompare(Params, MainV2.comPort.param, param2);
+                
+                ThemeManager.ApplyThemeTo(paramCompareForm);
+                paramCompareForm.ShowDialog();
+            }
+        }
+
+
+        private void BUT_rerequestparams_Click(object sender, EventArgs e)
+        {
+            if (!MainV2.comPort.BaseStream.IsOpen)
+                return;
+
+            ((Control)sender).Enabled = false;
+            
+            try
+            {
+                MainV2.comPort.getParamList();
+            }
+            catch (Exception ex)
+            {
+                log.Error("Exception getting param list", ex);
+                CustomMessageBox.Show("Error: getting param list");
+            }
+
+
+            ((Control)sender).Enabled = true;
+            
+            startup = true;
+
+            processToScreen();
+
+            startup = false;
+            
+            // Todo: this populates or the combos etc and what not. This shoudl prob be a bsv button
+            
+        }
+
+        void Params_CellValueChanged(object sender, DataGridViewCellEventArgs e)
+        {
+            if (e.RowIndex == -1 || e.ColumnIndex == -1 || startup == true || e.ColumnIndex != 1)
+                return;
+            try
+            {
+                if (Params[Command.Index, e.RowIndex].Value.ToString().EndsWith("_REV") && (Params[Command.Index, e.RowIndex].Value.ToString().StartsWith("RC") || Params[Command.Index, e.RowIndex].Value.ToString().StartsWith("HS")))
+                {
+                    if (Params[e.ColumnIndex, e.RowIndex].Value.ToString() == "0")
+                        Params[e.ColumnIndex, e.RowIndex].Value = "-1";
+                }
+
+                Params[e.ColumnIndex, e.RowIndex].Style.BackColor = Color.Green;
+                _changes[Params[0, e.RowIndex].Value] = float.Parse(Params[e.ColumnIndex, e.RowIndex].Value.ToString());
+            }
+            catch (Exception)
+            {
+                Params[e.ColumnIndex, e.RowIndex].Style.BackColor = Color.Red;
+            }
+
+        
+            Params.Focus();
+        }
+
+        void readToolTips()
+        {
+            System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Configuration));
+
+            string data = resources.GetString("MAVParam");
+
+            if (data == null)
+            {
+                data = global::ArdupilotMega.Properties.Resources.MAVParam;
+            }
+
+            string[] tips = data.Split(new char[] { '\r', '\n' }, StringSplitOptions.RemoveEmptyEntries);
+
+            foreach (var tip in tips)
+            {
+                if (!tip.StartsWith("||"))
+                    continue;
+
+                string[] cols = tip.Split(new string[] { "||" }, 9, StringSplitOptions.None);
+
+                if (cols.Length >= 8)
+                {
+                    paramsettings param = new paramsettings();
+                    try
+                    {
+                        param.name = cols[1];
+                        param.desc = AddNewLinesForTooltip(cols[7]);
+                        param.scale = float.Parse(cols[5]);
+                        param.minvalue = float.Parse(cols[2]);
+                        param.maxvalue = float.Parse(cols[3]);
+                        param.normalvalue = float.Parse(cols[4]);
+                    }
+                    catch { }
+                    tooltips[cols[1]] = param;
+                }
+
+            }
+        }
+
+        // from http://stackoverflow.com/questions/2512781/winforms-big-paragraph-tooltip/2512895#2512895
+        private const int maximumSingleLineTooltipLength = 50;
+
+        private static string AddNewLinesForTooltip(string text)
+        {
+            if (text.Length < maximumSingleLineTooltipLength)
+                return text;
+            int lineLength = (int)Math.Sqrt((double)text.Length) * 2;
+            StringBuilder sb = new StringBuilder();
+            int currentLinePosition = 0;
+            for (int textIndex = 0; textIndex < text.Length; textIndex++)
+            {
+                // If we have reached the target line length and the next      
+                // character is whitespace then begin a new line.   
+                if (currentLinePosition >= lineLength &&
+                    char.IsWhiteSpace(text[textIndex]))
+                {
+                    sb.Append(Environment.NewLine);
+                    currentLinePosition = 0;
+                }
+                // If we have just started a new line, skip all the whitespace.    
+                if (currentLinePosition == 0)
+                    while (textIndex < text.Length && char.IsWhiteSpace(text[textIndex]))
+                        textIndex++;
+                // Append the next character.     
+                if (textIndex < text.Length) sb.Append(text[textIndex]);
+                currentLinePosition++;
+            }
+            return sb.ToString();
+        }
+
+        internal void processToScreen()
+        {
+            toolTip1.RemoveAll();
+            Params.Rows.Clear();
+
+            // process hashdefines and update display
+            foreach (string value in MainV2.comPort.param.Keys)
+            {
+                if (value == null || value == "")
+                    continue;
+
+                //System.Diagnostics.Debug.WriteLine("Doing: " + value);
+
+                Params.Rows.Add();
+                Params.Rows[Params.RowCount - 1].Cells[Command.Index].Value = value;
+                Params.Rows[Params.RowCount - 1].Cells[Value.Index].Value = ((float)MainV2.comPort.param[value]).ToString("0.###");
+                try
+                {
+                    if (tooltips[value] != null)
+                    {
+                        Params.Rows[Params.RowCount - 1].Cells[Command.Index].ToolTipText = ((paramsettings)tooltips[value]).desc;
+                        //Params.Rows[Params.RowCount - 1].Cells[RawValue.Index].ToolTipText = ((paramsettings)tooltips[value]).desc;
+                        Params.Rows[Params.RowCount - 1].Cells[Value.Index].ToolTipText = ((paramsettings)tooltips[value]).desc;
+
+                        //Params.Rows[Params.RowCount - 1].Cells[Default.Index].Value = ((paramsettings)tooltips[value]).normalvalue;
+                        //Params.Rows[Params.RowCount - 1].Cells[mavScale.Index].Value = ((paramsettings)tooltips[value]).scale;
+                        //Params.Rows[Params.RowCount - 1].Cells[Value.Index].Value = float.Parse(Params.Rows[Params.RowCount - 1].Cells[RawValue.Index].Value.ToString()) / float.Parse(Params.Rows[Params.RowCount - 1].Cells[mavScale.Index].Value.ToString());
+                    }
+                }
+                catch { }
+
+            }
+            Params.Sort(Params.Columns[0], ListSortDirection.Ascending);
+        }
+
+        private void ConfigRawParams_Load(object sender, EventArgs e)
+        {
+            // read tooltips
+            if (tooltips.Count == 0)
+                readToolTips();
+
+            startup = true;
+
+            processToScreen();
+
+            startup = false;
+        }
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx
new file mode 100644
index 0000000000000000000000000000000000000000..a5480f3926deaeefb4646c4b220a1361f00f0004
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx
@@ -0,0 +1,135 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <metadata name="Command.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
+    <value>True</value>
+  </metadata>
+  <metadata name="Value.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
+    <value>True</value>
+  </metadata>
+  <metadata name="Default.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
+    <value>True</value>
+  </metadata>
+  <metadata name="RawValue.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
+    <value>True</value>
+  </metadata>
+  <metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
+    <value>17, 17</value>
+  </metadata>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs
new file mode 100644
index 0000000000000000000000000000000000000000..668c9742feffd92e04ad51b28a4e890c26f57512
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs
@@ -0,0 +1,763 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    partial class ConfigTradHeli
+    {
+        /// <summary> 
+        /// Required designer variable.
+        /// </summary>
+        private System.ComponentModel.IContainer components = null;
+
+        /// <summary> 
+        /// Clean up any resources being used.
+        /// </summary>
+        /// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
+        protected override void Dispose(bool disposing)
+        {
+            if (disposing && (components != null))
+            {
+                components.Dispose();
+            }
+            base.Dispose(disposing);
+        }
+
+        #region Component Designer generated code
+
+        /// <summary> 
+        /// Required method for Designer support - do not modify 
+        /// the contents of this method with the code editor.
+        /// </summary>
+        private void InitializeComponent()
+        {
+            this.components = new System.ComponentModel.Container();
+            System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigTradHeli));
+            this.groupBox5 = new System.Windows.Forms.GroupBox();
+            this.H1_ENABLE = new System.Windows.Forms.RadioButton();
+            this.CCPM = new System.Windows.Forms.RadioButton();
+            this.BUT_swash_manual = new ArdupilotMega.MyButton();
+            this.label41 = new System.Windows.Forms.Label();
+            this.groupBox3 = new System.Windows.Forms.GroupBox();
+            this.label46 = new System.Windows.Forms.Label();
+            this.label45 = new System.Windows.Forms.Label();
+            this.GYR_ENABLE = new System.Windows.Forms.CheckBox();
+            this.GYR_GAIN = new System.Windows.Forms.TextBox();
+            this.BUT_HS4save = new ArdupilotMega.MyButton();
+            this.label21 = new System.Windows.Forms.Label();
+            this.COL_MIN = new System.Windows.Forms.TextBox();
+            this.groupBox1 = new System.Windows.Forms.GroupBox();
+            this.COL_MID = new System.Windows.Forms.TextBox();
+            this.COL_MAX = new System.Windows.Forms.TextBox();
+            this.BUT_0collective = new ArdupilotMega.MyButton();
+            this.groupBox2 = new System.Windows.Forms.GroupBox();
+            this.label24 = new System.Windows.Forms.Label();
+            this.HS4_MIN = new System.Windows.Forms.TextBox();
+            this.HS4_MAX = new System.Windows.Forms.TextBox();
+            this.label40 = new System.Windows.Forms.Label();
+            this.HS3_TRIM = new System.Windows.Forms.NumericUpDown();
+            this.HS2_TRIM = new System.Windows.Forms.NumericUpDown();
+            this.HS1_TRIM = new System.Windows.Forms.NumericUpDown();
+            this.label39 = new System.Windows.Forms.Label();
+            this.label38 = new System.Windows.Forms.Label();
+            this.label37 = new System.Windows.Forms.Label();
+            this.label36 = new System.Windows.Forms.Label();
+            this.label26 = new System.Windows.Forms.Label();
+            this.PIT_MAX = new System.Windows.Forms.TextBox();
+            this.label25 = new System.Windows.Forms.Label();
+            this.ROL_MAX = new System.Windows.Forms.TextBox();
+            this.label23 = new System.Windows.Forms.Label();
+            this.label22 = new System.Windows.Forms.Label();
+            this.label20 = new System.Windows.Forms.Label();
+            this.label19 = new System.Windows.Forms.Label();
+            this.label18 = new System.Windows.Forms.Label();
+            this.SV3_POS = new System.Windows.Forms.TextBox();
+            this.SV2_POS = new System.Windows.Forms.TextBox();
+            this.SV1_POS = new System.Windows.Forms.TextBox();
+            this.HS3_REV = new System.Windows.Forms.CheckBox();
+            this.HS2_REV = new System.Windows.Forms.CheckBox();
+            this.HS1_REV = new System.Windows.Forms.CheckBox();
+            this.label17 = new System.Windows.Forms.Label();
+            this.HS4 = new ArdupilotMega.HorizontalProgressBar2();
+            this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components);
+            this.HS3 = new ArdupilotMega.VerticalProgressBar2();
+            this.Gservoloc = new AGaugeApp.AGauge();
+            this.label44 = new System.Windows.Forms.Label();
+            this.label43 = new System.Windows.Forms.Label();
+            this.label42 = new System.Windows.Forms.Label();
+            this.HS4_TRIM = new System.Windows.Forms.NumericUpDown();
+            this.HS4_REV = new System.Windows.Forms.CheckBox();
+            this.groupBox5.SuspendLayout();
+            this.groupBox3.SuspendLayout();
+            this.groupBox1.SuspendLayout();
+            this.groupBox2.SuspendLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.HS1_TRIM)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit();
+            ((System.ComponentModel.ISupportInitialize)(this.HS4_TRIM)).BeginInit();
+            this.SuspendLayout();
+            // 
+            // groupBox5
+            // 
+            this.groupBox5.Controls.Add(this.H1_ENABLE);
+            this.groupBox5.Controls.Add(this.CCPM);
+            resources.ApplyResources(this.groupBox5, "groupBox5");
+            this.groupBox5.Name = "groupBox5";
+            this.groupBox5.TabStop = false;
+            // 
+            // H1_ENABLE
+            // 
+            resources.ApplyResources(this.H1_ENABLE, "H1_ENABLE");
+            this.H1_ENABLE.Name = "H1_ENABLE";
+            this.H1_ENABLE.TabStop = true;
+            this.H1_ENABLE.UseVisualStyleBackColor = true;
+            this.H1_ENABLE.CheckedChanged += new System.EventHandler(this.H1_ENABLE_CheckedChanged);
+            // 
+            // CCPM
+            // 
+            resources.ApplyResources(this.CCPM, "CCPM");
+            this.CCPM.Name = "CCPM";
+            this.CCPM.TabStop = true;
+            this.CCPM.UseVisualStyleBackColor = true;
+            // 
+            // BUT_swash_manual
+            // 
+            resources.ApplyResources(this.BUT_swash_manual, "BUT_swash_manual");
+            this.BUT_swash_manual.Name = "BUT_swash_manual";
+            this.BUT_swash_manual.UseVisualStyleBackColor = true;
+            this.BUT_swash_manual.Click += new System.EventHandler(this.BUT_swash_manual_Click);
+            // 
+            // label41
+            // 
+            resources.ApplyResources(this.label41, "label41");
+            this.label41.Name = "label41";
+            // 
+            // groupBox3
+            // 
+            this.groupBox3.Controls.Add(this.label46);
+            this.groupBox3.Controls.Add(this.label45);
+            this.groupBox3.Controls.Add(this.GYR_ENABLE);
+            this.groupBox3.Controls.Add(this.GYR_GAIN);
+            resources.ApplyResources(this.groupBox3, "groupBox3");
+            this.groupBox3.Name = "groupBox3";
+            this.groupBox3.TabStop = false;
+            // 
+            // label46
+            // 
+            resources.ApplyResources(this.label46, "label46");
+            this.label46.Name = "label46";
+            // 
+            // label45
+            // 
+            resources.ApplyResources(this.label45, "label45");
+            this.label45.Name = "label45";
+            // 
+            // GYR_ENABLE
+            // 
+            resources.ApplyResources(this.GYR_ENABLE, "GYR_ENABLE");
+            this.GYR_ENABLE.Name = "GYR_ENABLE";
+            this.GYR_ENABLE.UseVisualStyleBackColor = true;
+            this.GYR_ENABLE.CheckedChanged += new System.EventHandler(this.GYR_ENABLE__CheckedChanged);
+            // 
+            // GYR_GAIN
+            // 
+            resources.ApplyResources(this.GYR_GAIN, "GYR_GAIN");
+            this.GYR_GAIN.Name = "GYR_GAIN";
+            this.GYR_GAIN.Validating += new System.ComponentModel.CancelEventHandler(this.GYR_GAIN__Validating);
+            // 
+            // BUT_HS4save
+            // 
+            resources.ApplyResources(this.BUT_HS4save, "BUT_HS4save");
+            this.BUT_HS4save.Name = "BUT_HS4save";
+            this.BUT_HS4save.UseVisualStyleBackColor = true;
+            this.BUT_HS4save.Click += new System.EventHandler(this.BUT_HS4save_Click);
+            // 
+            // label21
+            // 
+            resources.ApplyResources(this.label21, "label21");
+            this.label21.Name = "label21";
+            // 
+            // COL_MIN
+            // 
+            resources.ApplyResources(this.COL_MIN, "COL_MIN");
+            this.COL_MIN.Name = "COL_MIN";
+            // 
+            // groupBox1
+            // 
+            this.groupBox1.Controls.Add(this.label41);
+            this.groupBox1.Controls.Add(this.label21);
+            this.groupBox1.Controls.Add(this.COL_MIN);
+            this.groupBox1.Controls.Add(this.COL_MID);
+            this.groupBox1.Controls.Add(this.COL_MAX);
+            this.groupBox1.Controls.Add(this.BUT_0collective);
+            resources.ApplyResources(this.groupBox1, "groupBox1");
+            this.groupBox1.Name = "groupBox1";
+            this.groupBox1.TabStop = false;
+            // 
+            // COL_MID
+            // 
+            resources.ApplyResources(this.COL_MID, "COL_MID");
+            this.COL_MID.Name = "COL_MID";
+            this.COL_MID.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
+            // 
+            // COL_MAX
+            // 
+            resources.ApplyResources(this.COL_MAX, "COL_MAX");
+            this.COL_MAX.Name = "COL_MAX";
+            this.COL_MAX.Enter += new System.EventHandler(this.COL_MAX__Enter);
+            this.COL_MAX.Leave += new System.EventHandler(this.COL_MAX__Leave);
+            this.COL_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
+            // 
+            // BUT_0collective
+            // 
+            resources.ApplyResources(this.BUT_0collective, "BUT_0collective");
+            this.BUT_0collective.Name = "BUT_0collective";
+            this.BUT_0collective.UseVisualStyleBackColor = true;
+            this.BUT_0collective.Click += new System.EventHandler(this.BUT_0collective_Click);
+            // 
+            // groupBox2
+            // 
+            this.groupBox2.Controls.Add(this.label24);
+            this.groupBox2.Controls.Add(this.HS4_MIN);
+            this.groupBox2.Controls.Add(this.HS4_MAX);
+            this.groupBox2.Controls.Add(this.label40);
+            resources.ApplyResources(this.groupBox2, "groupBox2");
+            this.groupBox2.Name = "groupBox2";
+            this.groupBox2.TabStop = false;
+            // 
+            // label24
+            // 
+            resources.ApplyResources(this.label24, "label24");
+            this.label24.Name = "label24";
+            // 
+            // HS4_MIN
+            // 
+            resources.ApplyResources(this.HS4_MIN, "HS4_MIN");
+            this.HS4_MIN.Name = "HS4_MIN";
+            // 
+            // HS4_MAX
+            // 
+            resources.ApplyResources(this.HS4_MAX, "HS4_MAX");
+            this.HS4_MAX.Name = "HS4_MAX";
+            this.HS4_MAX.Enter += new System.EventHandler(this.HS4_MAX_Enter);
+            this.HS4_MAX.Leave += new System.EventHandler(this.HS4_MAX_Leave);
+            this.HS4_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
+            // 
+            // label40
+            // 
+            resources.ApplyResources(this.label40, "label40");
+            this.label40.Name = "label40";
+            // 
+            // HS3_TRIM
+            // 
+            resources.ApplyResources(this.HS3_TRIM, "HS3_TRIM");
+            this.HS3_TRIM.Maximum = new decimal(new int[] {
+            2000,
+            0,
+            0,
+            0});
+            this.HS3_TRIM.Minimum = new decimal(new int[] {
+            1000,
+            0,
+            0,
+            0});
+            this.HS3_TRIM.Name = "HS3_TRIM";
+            this.HS3_TRIM.Value = new decimal(new int[] {
+            1500,
+            0,
+            0,
+            0});
+            this.HS3_TRIM.ValueChanged += new System.EventHandler(this.HS3_TRIM_ValueChanged);
+            // 
+            // HS2_TRIM
+            // 
+            resources.ApplyResources(this.HS2_TRIM, "HS2_TRIM");
+            this.HS2_TRIM.Maximum = new decimal(new int[] {
+            2000,
+            0,
+            0,
+            0});
+            this.HS2_TRIM.Minimum = new decimal(new int[] {
+            1000,
+            0,
+            0,
+            0});
+            this.HS2_TRIM.Name = "HS2_TRIM";
+            this.HS2_TRIM.Value = new decimal(new int[] {
+            1500,
+            0,
+            0,
+            0});
+            this.HS2_TRIM.ValueChanged += new System.EventHandler(this.HS2_TRIM_ValueChanged);
+            // 
+            // HS1_TRIM
+            // 
+            resources.ApplyResources(this.HS1_TRIM, "HS1_TRIM");
+            this.HS1_TRIM.Maximum = new decimal(new int[] {
+            2000,
+            0,
+            0,
+            0});
+            this.HS1_TRIM.Minimum = new decimal(new int[] {
+            1000,
+            0,
+            0,
+            0});
+            this.HS1_TRIM.Name = "HS1_TRIM";
+            this.HS1_TRIM.Value = new decimal(new int[] {
+            1500,
+            0,
+            0,
+            0});
+            this.HS1_TRIM.ValueChanged += new System.EventHandler(this.HS1_TRIM_ValueChanged);
+            // 
+            // label39
+            // 
+            resources.ApplyResources(this.label39, "label39");
+            this.label39.Name = "label39";
+            // 
+            // label38
+            // 
+            resources.ApplyResources(this.label38, "label38");
+            this.label38.Name = "label38";
+            // 
+            // label37
+            // 
+            resources.ApplyResources(this.label37, "label37");
+            this.label37.Name = "label37";
+            // 
+            // label36
+            // 
+            resources.ApplyResources(this.label36, "label36");
+            this.label36.Name = "label36";
+            // 
+            // label26
+            // 
+            resources.ApplyResources(this.label26, "label26");
+            this.label26.Name = "label26";
+            // 
+            // PIT_MAX
+            // 
+            resources.ApplyResources(this.PIT_MAX, "PIT_MAX");
+            this.PIT_MAX.Name = "PIT_MAX";
+            this.PIT_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PIT_MAX__Validating);
+            // 
+            // label25
+            // 
+            resources.ApplyResources(this.label25, "label25");
+            this.label25.Name = "label25";
+            // 
+            // ROL_MAX
+            // 
+            resources.ApplyResources(this.ROL_MAX, "ROL_MAX");
+            this.ROL_MAX.Name = "ROL_MAX";
+            this.ROL_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.ROL_MAX__Validating);
+            // 
+            // label23
+            // 
+            resources.ApplyResources(this.label23, "label23");
+            this.label23.Name = "label23";
+            // 
+            // label22
+            // 
+            resources.ApplyResources(this.label22, "label22");
+            this.label22.Name = "label22";
+            // 
+            // label20
+            // 
+            resources.ApplyResources(this.label20, "label20");
+            this.label20.Name = "label20";
+            // 
+            // label19
+            // 
+            resources.ApplyResources(this.label19, "label19");
+            this.label19.Name = "label19";
+            // 
+            // label18
+            // 
+            resources.ApplyResources(this.label18, "label18");
+            this.label18.Name = "label18";
+            // 
+            // SV3_POS
+            // 
+            resources.ApplyResources(this.SV3_POS, "SV3_POS");
+            this.SV3_POS.Name = "SV3_POS";
+            this.SV3_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos3_Validating);
+            // 
+            // SV2_POS
+            // 
+            resources.ApplyResources(this.SV2_POS, "SV2_POS");
+            this.SV2_POS.Name = "SV2_POS";
+            this.SV2_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos2_Validating);
+            // 
+            // SV1_POS
+            // 
+            resources.ApplyResources(this.SV1_POS, "SV1_POS");
+            this.SV1_POS.Name = "SV1_POS";
+            this.SV1_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos1_Validating);
+            // 
+            // HS3_REV
+            // 
+            resources.ApplyResources(this.HS3_REV, "HS3_REV");
+            this.HS3_REV.Name = "HS3_REV";
+            this.HS3_REV.UseVisualStyleBackColor = true;
+            this.HS3_REV.CheckedChanged += new System.EventHandler(this.HS3_REV_CheckedChanged);
+            // 
+            // HS2_REV
+            // 
+            resources.ApplyResources(this.HS2_REV, "HS2_REV");
+            this.HS2_REV.Name = "HS2_REV";
+            this.HS2_REV.UseVisualStyleBackColor = true;
+            this.HS2_REV.CheckedChanged += new System.EventHandler(this.HS2_REV_CheckedChanged);
+            // 
+            // HS1_REV
+            // 
+            resources.ApplyResources(this.HS1_REV, "HS1_REV");
+            this.HS1_REV.Name = "HS1_REV";
+            this.HS1_REV.UseVisualStyleBackColor = true;
+            this.HS1_REV.CheckedChanged += new System.EventHandler(this.HS1_REV_CheckedChanged);
+            // 
+            // label17
+            // 
+            resources.ApplyResources(this.label17, "label17");
+            this.label17.Name = "label17";
+            // 
+            // HS4
+            // 
+            this.HS4.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
+            this.HS4.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+            this.HS4.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch4in", true));
+            this.HS4.Label = "Rudder";
+            resources.ApplyResources(this.HS4, "HS4");
+            this.HS4.Maximum = 2200;
+            this.HS4.maxline = 0;
+            this.HS4.Minimum = 800;
+            this.HS4.minline = 0;
+            this.HS4.Name = "HS4";
+            this.HS4.Value = 1500;
+            this.HS4.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31)))));
+            this.HS4.Paint += new System.Windows.Forms.PaintEventHandler(this.HS4_Paint);
+            // 
+            // currentStateBindingSource
+            // 
+            this.currentStateBindingSource.DataSource = typeof(ArdupilotMega.CurrentState);
+            // 
+            // HS3
+            // 
+            this.HS3.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
+            this.HS3.BorderColor = System.Drawing.SystemColors.ActiveBorder;
+            this.HS3.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch3in", true));
+            this.HS3.Label = "Collective";
+            resources.ApplyResources(this.HS3, "HS3");
+            this.HS3.Maximum = 2200;
+            this.HS3.maxline = 0;
+            this.HS3.Minimum = 800;
+            this.HS3.minline = 0;
+            this.HS3.Name = "HS3";
+            this.HS3.Value = 1500;
+            this.HS3.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31)))));
+            this.HS3.Paint += new System.Windows.Forms.PaintEventHandler(this.HS3_Paint);
+            // 
+            // Gservoloc
+            // 
+            this.Gservoloc.BackColor = System.Drawing.Color.Transparent;
+            this.Gservoloc.BackgroundImage = global::ArdupilotMega.Properties.Resources.Gaugebg;
+            resources.ApplyResources(this.Gservoloc, "Gservoloc");
+            this.Gservoloc.BaseArcColor = System.Drawing.Color.Transparent;
+            this.Gservoloc.BaseArcRadius = 60;
+            this.Gservoloc.BaseArcStart = 90;
+            this.Gservoloc.BaseArcSweep = 360;
+            this.Gservoloc.BaseArcWidth = 2;
+            this.Gservoloc.basesize = new System.Drawing.Size(150, 150);
+            this.Gservoloc.Cap_Idx = ((byte)(0));
+            this.Gservoloc.CapColor = System.Drawing.Color.White;
+            this.Gservoloc.CapColors = new System.Drawing.Color[] {
+        System.Drawing.Color.White,
+        System.Drawing.Color.Black,
+        System.Drawing.Color.Black,
+        System.Drawing.Color.Black,
+        System.Drawing.Color.Black};
+            this.Gservoloc.CapPosition = new System.Drawing.Point(55, 85);
+            this.Gservoloc.CapsPosition = new System.Drawing.Point[] {
+        new System.Drawing.Point(55, 85),
+        new System.Drawing.Point(40, 67),
+        new System.Drawing.Point(10, 10),
+        new System.Drawing.Point(10, 10),
+        new System.Drawing.Point(10, 10)};
+            this.Gservoloc.CapsText = new string[] {
+        "Position",
+        "",
+        "",
+        "",
+        ""};
+            this.Gservoloc.CapText = "Position";
+            this.Gservoloc.Center = new System.Drawing.Point(75, 75);
+            this.Gservoloc.MaxValue = 180F;
+            this.Gservoloc.MinValue = -180F;
+            this.Gservoloc.Name = "Gservoloc";
+            this.Gservoloc.Need_Idx = ((byte)(3));
+            this.Gservoloc.NeedleColor1 = AGaugeApp.AGauge.NeedleColorEnum.Gray;
+            this.Gservoloc.NeedleColor2 = System.Drawing.Color.White;
+            this.Gservoloc.NeedleEnabled = false;
+            this.Gservoloc.NeedleRadius = 80;
+            this.Gservoloc.NeedlesColor1 = new AGaugeApp.AGauge.NeedleColorEnum[] {
+        AGaugeApp.AGauge.NeedleColorEnum.Gray,
+        AGaugeApp.AGauge.NeedleColorEnum.Red,
+        AGaugeApp.AGauge.NeedleColorEnum.Green,
+        AGaugeApp.AGauge.NeedleColorEnum.Gray};
+            this.Gservoloc.NeedlesColor2 = new System.Drawing.Color[] {
+        System.Drawing.Color.White,
+        System.Drawing.Color.White,
+        System.Drawing.Color.White,
+        System.Drawing.Color.White};
+            this.Gservoloc.NeedlesEnabled = new bool[] {
+        true,
+        true,
+        true,
+        false};
+            this.Gservoloc.NeedlesRadius = new int[] {
+        60,
+        60,
+        60,
+        80};
+            this.Gservoloc.NeedlesType = new int[] {
+        0,
+        0,
+        0,
+        0};
+            this.Gservoloc.NeedlesWidth = new int[] {
+        2,
+        2,
+        2,
+        2};
+            this.Gservoloc.NeedleType = 0;
+            this.Gservoloc.NeedleWidth = 2;
+            this.Gservoloc.Range_Idx = ((byte)(0));
+            this.Gservoloc.RangeColor = System.Drawing.Color.LightGreen;
+            this.Gservoloc.RangeEnabled = false;
+            this.Gservoloc.RangeEndValue = 360F;
+            this.Gservoloc.RangeInnerRadius = 1;
+            this.Gservoloc.RangeOuterRadius = 60;
+            this.Gservoloc.RangesColor = new System.Drawing.Color[] {
+        System.Drawing.Color.LightGreen,
+        System.Drawing.Color.Red,
+        System.Drawing.Color.Orange,
+        System.Drawing.SystemColors.Control,
+        System.Drawing.SystemColors.Control};
+            this.Gservoloc.RangesEnabled = new bool[] {
+        false,
+        false,
+        false,
+        false,
+        false};
+            this.Gservoloc.RangesEndValue = new float[] {
+        360F,
+        200F,
+        150F,
+        0F,
+        0F};
+            this.Gservoloc.RangesInnerRadius = new int[] {
+        1,
+        1,
+        1,
+        70,
+        70};
+            this.Gservoloc.RangesOuterRadius = new int[] {
+        60,
+        60,
+        60,
+        80,
+        80};
+            this.Gservoloc.RangesStartValue = new float[] {
+        0F,
+        150F,
+        75F,
+        0F,
+        0F};
+            this.Gservoloc.RangeStartValue = 0F;
+            this.Gservoloc.ScaleLinesInterColor = System.Drawing.Color.White;
+            this.Gservoloc.ScaleLinesInterInnerRadius = 52;
+            this.Gservoloc.ScaleLinesInterOuterRadius = 60;
+            this.Gservoloc.ScaleLinesInterWidth = 1;
+            this.Gservoloc.ScaleLinesMajorColor = System.Drawing.Color.White;
+            this.Gservoloc.ScaleLinesMajorInnerRadius = 50;
+            this.Gservoloc.ScaleLinesMajorOuterRadius = 60;
+            this.Gservoloc.ScaleLinesMajorStepValue = 30F;
+            this.Gservoloc.ScaleLinesMajorWidth = 2;
+            this.Gservoloc.ScaleLinesMinorColor = System.Drawing.Color.White;
+            this.Gservoloc.ScaleLinesMinorInnerRadius = 55;
+            this.Gservoloc.ScaleLinesMinorNumOf = 2;
+            this.Gservoloc.ScaleLinesMinorOuterRadius = 60;
+            this.Gservoloc.ScaleLinesMinorWidth = 1;
+            this.Gservoloc.ScaleNumbersColor = System.Drawing.Color.White;
+            this.Gservoloc.ScaleNumbersFormat = null;
+            this.Gservoloc.ScaleNumbersRadius = 44;
+            this.Gservoloc.ScaleNumbersRotation = 45;
+            this.Gservoloc.ScaleNumbersStartScaleLine = 2;
+            this.Gservoloc.ScaleNumbersStepScaleLines = 1;
+            this.Gservoloc.Value = 0F;
+            this.Gservoloc.Value0 = -60F;
+            this.Gservoloc.Value1 = 60F;
+            this.Gservoloc.Value2 = 180F;
+            this.Gservoloc.Value3 = 0F;
+            // 
+            // label44
+            // 
+            resources.ApplyResources(this.label44, "label44");
+            this.label44.Name = "label44";
+            // 
+            // label43
+            // 
+            resources.ApplyResources(this.label43, "label43");
+            this.label43.Name = "label43";
+            // 
+            // label42
+            // 
+            resources.ApplyResources(this.label42, "label42");
+            this.label42.Name = "label42";
+            // 
+            // HS4_TRIM
+            // 
+            resources.ApplyResources(this.HS4_TRIM, "HS4_TRIM");
+            this.HS4_TRIM.Maximum = new decimal(new int[] {
+            2000,
+            0,
+            0,
+            0});
+            this.HS4_TRIM.Minimum = new decimal(new int[] {
+            1000,
+            0,
+            0,
+            0});
+            this.HS4_TRIM.Name = "HS4_TRIM";
+            this.HS4_TRIM.Value = new decimal(new int[] {
+            1500,
+            0,
+            0,
+            0});
+            this.HS4_TRIM.ValueChanged += new System.EventHandler(this.HS4_TRIM_ValueChanged);
+            // 
+            // HS4_REV
+            // 
+            resources.ApplyResources(this.HS4_REV, "HS4_REV");
+            this.HS4_REV.Name = "HS4_REV";
+            this.HS4_REV.UseVisualStyleBackColor = true;
+            this.HS4_REV.CheckedChanged += new System.EventHandler(this.HS4_REV_CheckedChanged);
+            // 
+            // ConfigTradHeli
+            // 
+            resources.ApplyResources(this, "$this");
+            this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
+            this.Controls.Add(this.label44);
+            this.Controls.Add(this.label43);
+            this.Controls.Add(this.label42);
+            this.Controls.Add(this.HS4_TRIM);
+            this.Controls.Add(this.HS4_REV);
+            this.Controls.Add(this.groupBox5);
+            this.Controls.Add(this.BUT_swash_manual);
+            this.Controls.Add(this.groupBox3);
+            this.Controls.Add(this.BUT_HS4save);
+            this.Controls.Add(this.groupBox1);
+            this.Controls.Add(this.groupBox2);
+            this.Controls.Add(this.HS3_TRIM);
+            this.Controls.Add(this.HS2_TRIM);
+            this.Controls.Add(this.HS1_TRIM);
+            this.Controls.Add(this.label39);
+            this.Controls.Add(this.label38);
+            this.Controls.Add(this.label37);
+            this.Controls.Add(this.label36);
+            this.Controls.Add(this.label26);
+            this.Controls.Add(this.PIT_MAX);
+            this.Controls.Add(this.label25);
+            this.Controls.Add(this.ROL_MAX);
+            this.Controls.Add(this.label23);
+            this.Controls.Add(this.label22);
+            this.Controls.Add(this.label20);
+            this.Controls.Add(this.label19);
+            this.Controls.Add(this.label18);
+            this.Controls.Add(this.SV3_POS);
+            this.Controls.Add(this.SV2_POS);
+            this.Controls.Add(this.SV1_POS);
+            this.Controls.Add(this.HS3_REV);
+            this.Controls.Add(this.HS2_REV);
+            this.Controls.Add(this.HS1_REV);
+            this.Controls.Add(this.label17);
+            this.Controls.Add(this.HS4);
+            this.Controls.Add(this.HS3);
+            this.Controls.Add(this.Gservoloc);
+            this.Name = "ConfigTradHeli";
+            this.Load += new System.EventHandler(this.ConfigTradHeli_Load);
+            this.groupBox5.ResumeLayout(false);
+            this.groupBox5.PerformLayout();
+            this.groupBox3.ResumeLayout(false);
+            this.groupBox3.PerformLayout();
+            this.groupBox1.ResumeLayout(false);
+            this.groupBox1.PerformLayout();
+            this.groupBox2.ResumeLayout(false);
+            this.groupBox2.PerformLayout();
+            ((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.HS1_TRIM)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit();
+            ((System.ComponentModel.ISupportInitialize)(this.HS4_TRIM)).EndInit();
+            this.ResumeLayout(false);
+            this.PerformLayout();
+
+        }
+
+        #endregion
+
+        private System.Windows.Forms.GroupBox groupBox5;
+        private System.Windows.Forms.RadioButton H1_ENABLE;
+        private System.Windows.Forms.RadioButton CCPM;
+        private MyButton BUT_swash_manual;
+        private System.Windows.Forms.Label label41;
+        private System.Windows.Forms.GroupBox groupBox3;
+        private System.Windows.Forms.Label label46;
+        private System.Windows.Forms.Label label45;
+        private System.Windows.Forms.CheckBox GYR_ENABLE;
+        private System.Windows.Forms.TextBox GYR_GAIN;
+        private MyButton BUT_HS4save;
+        private System.Windows.Forms.Label label21;
+        private System.Windows.Forms.TextBox COL_MIN;
+        private System.Windows.Forms.GroupBox groupBox1;
+        private System.Windows.Forms.TextBox COL_MID;
+        private System.Windows.Forms.TextBox COL_MAX;
+        private MyButton BUT_0collective;
+        private System.Windows.Forms.GroupBox groupBox2;
+        private System.Windows.Forms.Label label24;
+        private System.Windows.Forms.TextBox HS4_MIN;
+        private System.Windows.Forms.TextBox HS4_MAX;
+        private System.Windows.Forms.Label label40;
+        private System.Windows.Forms.NumericUpDown HS3_TRIM;
+        private System.Windows.Forms.NumericUpDown HS2_TRIM;
+        private System.Windows.Forms.NumericUpDown HS1_TRIM;
+        private System.Windows.Forms.Label label39;
+        private System.Windows.Forms.Label label38;
+        private System.Windows.Forms.Label label37;
+        private System.Windows.Forms.Label label36;
+        private System.Windows.Forms.Label label26;
+        private System.Windows.Forms.TextBox PIT_MAX;
+        private System.Windows.Forms.Label label25;
+        private System.Windows.Forms.TextBox ROL_MAX;
+        private System.Windows.Forms.Label label23;
+        private System.Windows.Forms.Label label22;
+        private System.Windows.Forms.Label label20;
+        private System.Windows.Forms.Label label19;
+        private System.Windows.Forms.Label label18;
+        private System.Windows.Forms.TextBox SV3_POS;
+        private System.Windows.Forms.TextBox SV2_POS;
+        private System.Windows.Forms.TextBox SV1_POS;
+        private System.Windows.Forms.CheckBox HS3_REV;
+        private System.Windows.Forms.CheckBox HS2_REV;
+        private System.Windows.Forms.CheckBox HS1_REV;
+        private System.Windows.Forms.Label label17;
+        private HorizontalProgressBar2 HS4;
+        private VerticalProgressBar2 HS3;
+        private AGaugeApp.AGauge Gservoloc;
+        private System.Windows.Forms.BindingSource currentStateBindingSource;
+        private System.Windows.Forms.Label label44;
+        private System.Windows.Forms.Label label43;
+        private System.Windows.Forms.Label label42;
+        private System.Windows.Forms.NumericUpDown HS4_TRIM;
+        private System.Windows.Forms.CheckBox HS4_REV;
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs
new file mode 100644
index 0000000000000000000000000000000000000000..59522dfaf5434378ca2552f314d64d19b25d8c7c
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs
@@ -0,0 +1,489 @@
+using System;
+using System.Collections.Generic;
+using System.ComponentModel;
+using System.Drawing;
+using System.Data;
+using System.Linq;
+using System.Text;
+using System.Windows.Forms;
+using ArdupilotMega.Controls.BackstageView;
+
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    public partial class ConfigTradHeli : BackStageViewContentPanel
+    {
+        bool startup = false;
+        bool inpwmdetect = false;
+
+        Timer timer = new Timer();
+
+        public ConfigTradHeli()
+        {
+            InitializeComponent();
+        }
+
+        private void H1_ENABLE_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            try
+            {
+                if (MainV2.comPort.param["H1_ENABLE"] == null)
+                {
+                    CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
+                }
+                else
+                {
+                    MainV2.comPort.setParam("H1_ENABLE", ((RadioButton)sender).Checked == true ? 1 : 0);
+                }
+            }
+            catch { CustomMessageBox.Show("Set H1_ENABLE Failed"); }
+        }
+
+        private void BUT_swash_manual_Click(object sender, EventArgs e)
+        {
+            try
+            {
+                if (MainV2.comPort.param["HSV_MAN"].ToString() == "1")
+                {
+                    MainV2.comPort.setParam("COL_MIN", int.Parse(COL_MIN.Text));
+                    MainV2.comPort.setParam("COL_MAX", int.Parse(COL_MAX.Text));
+                    MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
+                    BUT_swash_manual.Text = "Manual";
+
+                    COL_MAX.Enabled = false;
+                    COL_MID.Enabled = false;
+                    COL_MIN.Enabled = false;
+                    BUT_0collective.Enabled = false;
+                }
+                else
+                {
+                    COL_MAX.Text = "1500";
+                    COL_MIN.Text = "1500";
+                    MainV2.comPort.setParam("HSV_MAN", 1); // randy request
+                    BUT_swash_manual.Text = "Save";
+
+                    COL_MAX.Enabled = true;
+                    COL_MID.Enabled = true;
+                    COL_MIN.Enabled = true;
+                    BUT_0collective.Enabled = true;
+                }
+            }
+            catch { CustomMessageBox.Show("Failed to set HSV_MAN"); }
+        }
+
+        private void BUT_HS4save_Click(object sender, EventArgs e)
+        {
+            try
+            {
+                if (MainV2.comPort.param["HSV_MAN"].ToString() == "1")
+                {
+                    MainV2.comPort.setParam("HS4_MIN", int.Parse(HS4_MIN.Text));
+                    MainV2.comPort.setParam("HS4_MAX", int.Parse(HS4_MAX.Text));
+                    MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
+                    BUT_HS4save.Text = "Manual";
+
+                    HS4_MAX.Enabled = false;
+                    HS4_MIN.Enabled = false;
+                }
+                else
+                {
+                    HS4_MIN.Text = "1500";
+                    HS4_MAX.Text = "1500";
+                    MainV2.comPort.setParam("HSV_MAN", 1); // randy request
+                    BUT_HS4save.Text = "Save";
+
+
+                    HS4_MAX.Enabled = true;
+                    HS4_MIN.Enabled = true;
+                }
+            }
+            catch { CustomMessageBox.Show("Failed to set HSV_MAN"); }
+        }
+
+        private void tabHeli_Click(object sender, EventArgs e)
+        {
+
+        }
+
+        private void HS4_Paint(object sender, PaintEventArgs e)
+        {
+            try
+            {
+                if (int.Parse(HS4_MIN.Text) > HS4.minline)
+                    HS4_MIN.Text = HS4.minline.ToString();
+                if (int.Parse(HS4_MAX.Text) < HS4.maxline)
+                    HS4_MAX.Text = HS4.maxline.ToString();
+            }
+            catch { }
+        }
+
+        private void HS3_Paint(object sender, PaintEventArgs e)
+        {
+            try
+            {
+                if (int.Parse(COL_MIN.Text) > HS3.minline)
+                    COL_MIN.Text = HS3.minline.ToString();
+                if (int.Parse(COL_MAX.Text) < HS3.maxline)
+                    COL_MAX.Text = HS3.maxline.ToString();
+            }
+            catch { }
+        }
+
+        private void COL_MAX__Enter(object sender, EventArgs e)
+        {
+            inpwmdetect = true;
+        }
+
+        private void COL_MIN__Enter(object sender, EventArgs e)
+        {
+            inpwmdetect = true;
+        }
+
+        private void COL_MAX__Leave(object sender, EventArgs e)
+        {
+            inpwmdetect = false;
+        }
+
+        private void COL_MIN__Leave(object sender, EventArgs e)
+        {
+            inpwmdetect = false;
+        }
+
+        private void HS4_MIN_Enter(object sender, EventArgs e)
+        {
+            inpwmdetect = true;
+        }
+
+        private void HS4_MIN_Leave(object sender, EventArgs e)
+        {
+            inpwmdetect = false;
+        }
+
+        private void HS4_MAX_Enter(object sender, EventArgs e)
+        {
+            inpwmdetect = true;
+        }
+
+        private void HS4_MAX_Leave(object sender, EventArgs e)
+        {
+            inpwmdetect = false;
+        }
+
+        private void PWM_Validating(object sender, CancelEventArgs e)
+        {
+            Control temp = (Control)(sender);
+
+            if (int.Parse(temp.Text) < 900)
+                temp.Text = "900";
+            if (int.Parse(temp.Text) > 2100)
+                temp.Text = "2100";
+        }
+
+        private void TXT_srvpos1_Validating(object sender, CancelEventArgs e)
+        {
+            if (startup || this.Disposing)
+                return;
+            int test = 0;
+            if (!int.TryParse(((TextBox)sender).Text, out test))
+            {
+                e.Cancel = true;
+            }
+
+            Gservoloc.Value0 = test;
+
+            try
+            {
+                MainV2.comPort.setParam("HSV_MAN", 1); // randy request
+                MainV2.comPort.setParam(((TextBox)sender).Name, test);
+                System.Threading.Thread.Sleep(100);
+                MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
+
+            }
+            catch { CustomMessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
+        }
+
+        private void TXT_srvpos2_Validating(object sender, CancelEventArgs e)
+        {
+            if (startup || this.Disposing)
+                return;
+            int test = 0;
+            if (!int.TryParse(((TextBox)sender).Text, out test))
+            {
+                e.Cancel = true;
+            }
+
+            Gservoloc.Value1 = test;
+
+            try
+            {
+                MainV2.comPort.setParam("HSV_MAN", 1); // randy request
+                MainV2.comPort.setParam(((TextBox)sender).Name, test);
+                System.Threading.Thread.Sleep(100);
+                MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
+            }
+            catch { CustomMessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
+        }
+
+        private void TXT_srvpos3_Validating(object sender, CancelEventArgs e)
+        {
+            if (startup || this.Disposing)
+                return;
+            int test = 0;
+            if (!int.TryParse(((TextBox)sender).Text, out test))
+            {
+                e.Cancel = true;
+            }
+
+            Gservoloc.Value2 = test;
+
+            try
+            {
+                MainV2.comPort.setParam("HSV_MAN", 1); // randy request
+                MainV2.comPort.setParam(((TextBox)sender).Name, test);
+                System.Threading.Thread.Sleep(100);
+                MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
+            }
+            catch { CustomMessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
+        }
+
+        private void BUT_0collective_Click(object sender, EventArgs e)
+        {
+            CustomMessageBox.Show("Make sure your blades are at 0 degrees");
+
+            try
+            {
+
+                MainV2.comPort.setParam("COL_MID", MainV2.cs.ch3in);
+
+                COL_MID.Text = MainV2.comPort.param["COL_MID"].ToString();
+            }
+            catch { CustomMessageBox.Show("Set COL_MID_ failed"); }
+        }
+
+        private void HS1_REV_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == false ? 1.0f : -1.0f);
+        }
+
+        private void HS2_REV_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == false ? 1.0f : -1.0f);
+        }
+
+        private void HS3_REV_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == false ? 1.0f : -1.0f);
+        }
+
+        private void HS4_REV_CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == false ? 1.0f : -1.0f);
+        }
+
+        private void HS1_TRIM_ValueChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            MainV2.comPort.setParam(((NumericUpDown)sender).Name, (float)((NumericUpDown)sender).Value);
+        }
+
+        private void HS2_TRIM_ValueChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            MainV2.comPort.setParam(((NumericUpDown)sender).Name, (float)((NumericUpDown)sender).Value);
+        }
+
+        private void HS3_TRIM_ValueChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            MainV2.comPort.setParam(((NumericUpDown)sender).Name, (float)((NumericUpDown)sender).Value);
+        }
+
+        private void HS4_TRIM_ValueChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            MainV2.comPort.setParam(((NumericUpDown)sender).Name, (float)((NumericUpDown)sender).Value);
+        }
+
+        private void ROL_MAX__Validating(object sender, CancelEventArgs e)
+        {
+            if (startup || this.Disposing)
+                return;
+            int test = 0;
+            if (!int.TryParse(((TextBox)sender).Text, out test))
+            {
+                e.Cancel = true;
+            }
+
+            MainV2.comPort.setParam(((TextBox)sender).Name, test);
+        }
+
+        private void PIT_MAX__Validating(object sender, CancelEventArgs e)
+        {
+            if (startup || this.Disposing)
+                return;
+            int test = 0;
+            if (!int.TryParse(((TextBox)sender).Text, out test))
+            {
+                e.Cancel = true;
+            }
+
+            MainV2.comPort.setParam(((TextBox)sender).Name, test);
+        }
+
+        private void GYR_GAIN__Validating(object sender, CancelEventArgs e)
+        {
+            if (startup || this.Disposing || ((TextBox)sender).Enabled == false)
+                return;
+            int test = 0;
+            if (!int.TryParse(((TextBox)sender).Text, out test))
+            {
+                e.Cancel = true;
+            }
+
+            try
+            {
+                MainV2.comPort.setParam(((TextBox)sender).Name, test);
+            }
+            catch { CustomMessageBox.Show("Failed to set Gyro Gain"); }
+        }
+
+        private void GYR_ENABLE__CheckedChanged(object sender, EventArgs e)
+        {
+            if (startup)
+                return;
+            MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == true ? 1.0f : 0.0f);
+        }
+
+        private void ConfigTradHeli_Load(object sender, EventArgs e)
+        {
+            if (!MainV2.comPort.BaseStream.IsOpen)
+            {
+                this.Enabled = false;
+                return;
+            }
+            else
+            {
+                this.Enabled = true;
+            }
+
+            if (MainV2.comPort.param["GYR_ENABLE"] == null)
+            {
+                this.Enabled = false;
+                return;
+            }
+
+            timer.Tick += new EventHandler(timer_Tick);
+
+            timer.Enabled = true;
+            timer.Interval = 100;
+            timer.Start();
+
+            startup = true;
+            try
+            {
+                if (MainV2.comPort.param.ContainsKey("H1_ENABLE"))
+                {
+                    CCPM.Checked = MainV2.comPort.param["H1_ENABLE"].ToString() == "0" ? true : false;
+                    H1_ENABLE.Checked = !CCPM.Checked;
+                }
+
+                foreach (string value in MainV2.comPort.param.Keys)
+                {
+                    if (value == "")
+                        continue;
+
+                    Control[] control = this.Controls.Find(value, true);
+                    if (control.Length > 0)
+                    {
+                        if (control[0].GetType() == typeof(TextBox))
+                        {
+                            TextBox temp = (TextBox)control[0];
+                            string option = MainV2.comPort.param[value].ToString();
+                            temp.Text = option;
+                        }
+                        if (control[0].GetType() == typeof(NumericUpDown))
+                        {
+                            NumericUpDown temp = (NumericUpDown)control[0];
+                            string option = MainV2.comPort.param[value].ToString();
+                            temp.Text = option;
+                        }
+                        if (control[0].GetType() == typeof(CheckBox))
+                        {
+                            CheckBox temp = (CheckBox)control[0];
+                            string option = MainV2.comPort.param[value].ToString();
+                            temp.Checked = option == "1" ? true : false;
+                        }
+                        if (control[0].GetType() == typeof(MyTrackBar))
+                        {
+                            MyTrackBar temp = (MyTrackBar)control[0];
+                            string option = MainV2.comPort.param[value].ToString();
+                            temp.Value = int.Parse(option);
+                        }
+                    }
+                }
+
+                HS1_REV.Checked = MainV2.comPort.param["HS1_REV"].ToString() == "-1";
+                HS2_REV.Checked = MainV2.comPort.param["HS2_REV"].ToString() == "-1";
+                HS3_REV.Checked = MainV2.comPort.param["HS3_REV"].ToString() == "-1";
+                HS4_REV.Checked = MainV2.comPort.param["HS4_REV"].ToString() == "-1";
+
+            }
+            catch { }
+            startup = false;
+        }
+
+        void timer_Tick(object sender, EventArgs e)
+        {
+            try
+            {
+                MainV2.cs.UpdateCurrentSettings(currentStateBindingSource);
+            }
+            catch { }
+
+            if (MainV2.comPort.param["HSV_MAN"] == null || MainV2.comPort.param["HSV_MAN"].ToString() == "0")
+                return;
+
+            if (HS3.minline == 0)
+                HS3.minline = 2200;
+
+            if (HS4.minline == 0)
+                HS4.minline = 2200;
+
+            HS3.minline = Math.Min(HS3.minline, (int)MainV2.cs.ch3in);
+            HS3.maxline = Math.Max(HS3.maxline, (int)MainV2.cs.ch3in);
+
+            HS4.minline = Math.Min(HS4.minline, (int)MainV2.cs.ch4in);
+            HS4.maxline = Math.Max(HS4.maxline, (int)MainV2.cs.ch4in);
+
+            if (!inpwmdetect)
+            {
+                HS3_Paint(null, null);
+                HS4_Paint(null, null);
+            }
+            else
+            {
+                try
+                {
+                    HS3.minline = int.Parse(COL_MIN.Text);
+                    HS3.maxline = int.Parse(COL_MAX.Text);
+                    HS4.maxline = int.Parse(HS4_MIN.Text);
+                    HS4.minline = int.Parse(HS4_MAX.Text);
+                }
+                catch { }
+            }
+        }
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.es-ES.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.es-ES.resx
new file mode 100644
index 0000000000000000000000000000000000000000..70ad73f1af84a8cec236442b9c51462353fceab5
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.es-ES.resx
@@ -0,0 +1,315 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manual</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Modo actual:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Habilitar el flujo óptico</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>NOTA: Las imágenes son sólo para su presentación</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Actual:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APMSetup</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Swash-Servo posición</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Activar Compas</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Ajuste Chásis (+ or x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modos</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Modo Simple</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Reset</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Superior</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Swash de Viaje</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manual</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Timón de Viaje</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibración del sensor de voltaje:Para calibrar el sensor, use un multímetro para medir la tensión que sale de la CES de la batería-la eliminación del circuito (se trata de cables negro y rojo en el cable de tres hilos que suministra energía a la placa APM).Luego reste 0,3 V de ese valor y entrar en él en el campo # 1 a la izquierda.</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrar Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Modo de Vuelo 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Alabeo Max</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Modo de Vuelo 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Cabeceo Max</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>por ejemplo, en grados 2 ° 3 'W es -2,3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Modo de Vuelo 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Nivel tu quad para establecer las compensaciones por defecto acel</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Modo de Vuelo 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacidad</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Declinación</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Activar Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Entrada Radio</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibración</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Modo de Vuelo 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Modo de Vuelo 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Gyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Sitio Web Declinación</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batería</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Cero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Activar Airspeed</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Restablecer los Ajustes de hardware APM</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.fr.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.fr.resx
new file mode 100644
index 0000000000000000000000000000000000000000..1bd274beea2e052315a0ab1e83d3619dcf47cbf1
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.fr.resx
@@ -0,0 +1,312 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manuel</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Mode Courant:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Activ. capteur optique</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>NOTE: images pou presentation uniquement. Fonctionnel pour Hex, Octo etc...</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Actuel:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APMSetup</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Swash-Servo position</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Activ. Boussole</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>type de châssis (+ ou x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modes</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Mode Simple</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Réinit.</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Haut</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Mouvement Swash</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manuel</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Deplac. du Gouvernail</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibration du capteur de Voltage.1. Mesurer le voltage sur APM et inscrivez-le dans la boite ci-bas.2. Mesurer le voltage de la batterie et inscrivez-le dans la boite ci-bas.3. Inscrire les ampères par volt de la documentation du capteur de courant ci-bas</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrer Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Mode de vol 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Roulis Max</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Mode de vol 2</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Tangage Max</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>en degrés eg 2° 3' W est -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Mode de vol 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Niveler l'apareil pour copensation des accels</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Mode de vol 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacité</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Déclination</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Activer Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Entrée Radio</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Mode de vol 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Mode de vol 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Gyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Matériel</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Site Web Déclination</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batterie</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zéro</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Activ. Airspeed</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>RàZ tout parametres du APM</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Moniteur</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.it-IT.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.it-IT.resx
new file mode 100644
index 0000000000000000000000000000000000000000..2b2636c8132c76e5855c9dbb2c87151786f287c3
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.it-IT.resx
@@ -0,0 +1,318 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manuale</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Modo Corrente:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Abilita Flusso ottico</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>Nota: le immagini sono sono per presentazione, funzionerà con Hexa, etc.</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevatore CH1 Rev</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>PWM Corrente:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>Imposta APM</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Posizione del servo del piatto</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Abilita Magnetometro</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Imposta Frame (+ or x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modi</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Modo Semplice</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Riavvia</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Alto</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Escursione del piatto</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Manuale</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Escursione Timone</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Calibarzione del sensore di voltaggio:
+1. Misura il valtaggio di ingresso di APM e inseriscilo nel box sotto 
+2. Misura il voltaggio della batteria e inseriscilo nel box sotto 
+3. Dalle caratteristiche del sensore di corrente, inserisci il valore degli ampere per volt nel box qui sotto</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Calibrazione Radio</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Massimo</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Modo di volo 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Rollio massimo</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Modo di volo 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Passo massimo</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>in gradi es 2° 3' W is -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Modo di volo 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Livella il quad per impostare gli accelerometri</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Modo di volo 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Capacità</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Declinazione</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Attiva Sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Ingresso Radio</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibration</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Modo di volo 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Modo di volo 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Giroscopio</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Sito Web per la Declinazione</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Batteria</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Attiva Sensore Velocità</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Resetta APM ai valori di Default</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.pl.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.pl.resx
new file mode 100644
index 0000000000000000000000000000000000000000..057b9327168c6471be22139b5d017e20582de843
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.pl.resx
@@ -0,0 +1,318 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="SV3_POS_.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Ręczne</value>
+  </data>
+  <data name="label12.Text" xml:space="preserve">
+    <value>PWM 0 - 1230</value>
+  </data>
+  <data name="label10.Text" xml:space="preserve">
+    <value>PWM 1621 - 1749</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>Aktualny tryb:</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>Włącz Optical Flow</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>UWAGA: Obrazy są wyłącznie do prezentacji, działają jedynie z hexa, itp.</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label11.Text" xml:space="preserve">
+    <value>PWM 1750 +</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Odwr. Elevon CH1</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>Aktualny PWM:</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>Ustawienia APM</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Pozycja serwa płyty ster.</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>Włącz kompas</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>Ustawienie ramy (+ lub x)</value>
+  </data>
+  <data name="SV2_POS_.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Tryby</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>Tryb prosty</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Reset</value>
+  </data>
+  <data name="SV1_POS_.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Góra</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Zakres ruchu płyty sterującej</value>
+  </data>
+  <data name="lbl_currentmode.Text" xml:space="preserve">
+    <value>Ręczne</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Zakres steru kierunku</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>Kalibracja czujnika napięcia:
+1. Zmierz napięcie wejściowe APM i wpisz poniżej
+2. Zmierz napięcie baterii i wpisz poniżej
+3. Wpisz poniżej ilość amperów/wolt [A/V] z dokumentacji czujnika prądu</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>Kalibracja radia</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>Tryb lotu 2</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Max przechylenie</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>Tryb lotu 3</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Max pochylenie</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>w stopniech np. 2° 3' W to -2.3</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>Tryb lotu 1</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>Wypoziomuj quada żeby stawić domyśle offsety przysp.</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>Tryb lotu 6</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>Pojemność</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>Deklinacja</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>Włącz sonar</value>
+  </data>
+  <data name="label7.Text" xml:space="preserve">
+    <value>PWM 1231 - 1360</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Wejścia radia</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibration</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>Tryb lotu 4</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>Tryb lotu 5</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Żyro</value>
+  </data>
+  <data name="label8.Text" xml:space="preserve">
+    <value>PWM 1361 - 1490</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
+  </data>
+  <data name="label9.Text" xml:space="preserve">
+    <value>PWM 1491 - 1620</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>Strona www deklinacji</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Bateria</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zero</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>Włącz prędkość powietrza</value>
+  </data>
+  <data name="PIT_MAX_.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>Reset APM do stawień domyślnych</value>
+  </data>
+  <data name="GYR_GAIN_.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>Monitor</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx
new file mode 100644
index 0000000000000000000000000000000000000000..eb30a08ab96978bb941d664e74d675a24c560f41
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx
@@ -0,0 +1,1581 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
+  <data name="H1_ENABLE.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
+  <data name="H1_ENABLE.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="H1_ENABLE.Location" type="System.Drawing.Point, System.Drawing">
+    <value>67, 19</value>
+  </data>
+  <data name="H1_ENABLE.Size" type="System.Drawing.Size, System.Drawing">
+    <value>39, 17</value>
+  </data>
+  <data name="H1_ENABLE.TabIndex" type="System.Int32, mscorlib">
+    <value>137</value>
+  </data>
+  <data name="H1_ENABLE.Text" xml:space="preserve">
+    <value>H1</value>
+  </data>
+  <data name="&gt;&gt;H1_ENABLE.Name" xml:space="preserve">
+    <value>H1_ENABLE</value>
+  </data>
+  <data name="&gt;&gt;H1_ENABLE.Type" xml:space="preserve">
+    <value>System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;H1_ENABLE.Parent" xml:space="preserve">
+    <value>groupBox5</value>
+  </data>
+  <data name="&gt;&gt;H1_ENABLE.ZOrder" xml:space="preserve">
+    <value>0</value>
+  </data>
+  <data name="CCPM.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="CCPM.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="CCPM.Location" type="System.Drawing.Point, System.Drawing">
+    <value>6, 19</value>
+  </data>
+  <data name="CCPM.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 17</value>
+  </data>
+  <data name="CCPM.TabIndex" type="System.Int32, mscorlib">
+    <value>136</value>
+  </data>
+  <data name="CCPM.Text" xml:space="preserve">
+    <value>CCPM</value>
+  </data>
+  <data name="&gt;&gt;CCPM.Name" xml:space="preserve">
+    <value>CCPM</value>
+  </data>
+  <data name="&gt;&gt;CCPM.Type" xml:space="preserve">
+    <value>System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;CCPM.Parent" xml:space="preserve">
+    <value>groupBox5</value>
+  </data>
+  <data name="&gt;&gt;CCPM.ZOrder" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="groupBox5.Location" type="System.Drawing.Point, System.Drawing">
+    <value>257, 11</value>
+  </data>
+  <data name="groupBox5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>120, 43</value>
+  </data>
+  <data name="groupBox5.TabIndex" type="System.Int32, mscorlib">
+    <value>169</value>
+  </data>
+  <data name="groupBox5.Text" xml:space="preserve">
+    <value>Swash Type</value>
+  </data>
+  <data name="&gt;&gt;groupBox5.Name" xml:space="preserve">
+    <value>groupBox5</value>
+  </data>
+  <data name="&gt;&gt;groupBox5.Type" xml:space="preserve">
+    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;groupBox5.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;groupBox5.ZOrder" xml:space="preserve">
+    <value>5</value>
+  </data>
+  <data name="BUT_swash_manual.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="BUT_swash_manual.Location" type="System.Drawing.Point, System.Drawing">
+    <value>302, 83</value>
+  </data>
+  <data name="BUT_swash_manual.Size" type="System.Drawing.Size, System.Drawing">
+    <value>69, 23</value>
+  </data>
+  <data name="BUT_swash_manual.TabIndex" type="System.Int32, mscorlib">
+    <value>138</value>
+  </data>
+  <data name="BUT_swash_manual.Text" xml:space="preserve">
+    <value>Manual</value>
+  </data>
+  <data name="&gt;&gt;BUT_swash_manual.Name" xml:space="preserve">
+    <value>BUT_swash_manual</value>
+  </data>
+  <data name="&gt;&gt;BUT_swash_manual.Type" xml:space="preserve">
+    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;BUT_swash_manual.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;BUT_swash_manual.ZOrder" xml:space="preserve">
+    <value>6</value>
+  </data>
+  <data name="label41.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label41.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label41.Location" type="System.Drawing.Point, System.Drawing">
+    <value>19, 157</value>
+  </data>
+  <data name="label41.Size" type="System.Drawing.Size, System.Drawing">
+    <value>40, 13</value>
+  </data>
+  <data name="label41.TabIndex" type="System.Int32, mscorlib">
+    <value>122</value>
+  </data>
+  <data name="label41.Text" xml:space="preserve">
+    <value>Bottom</value>
+  </data>
+  <data name="&gt;&gt;label41.Name" xml:space="preserve">
+    <value>label41</value>
+  </data>
+  <data name="&gt;&gt;label41.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label41.Parent" xml:space="preserve">
+    <value>groupBox1</value>
+  </data>
+  <data name="&gt;&gt;label41.ZOrder" xml:space="preserve">
+    <value>0</value>
+  </data>
+  <data name="label46.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label46.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label46.Location" type="System.Drawing.Point, System.Drawing">
+    <value>6, 38</value>
+  </data>
+  <data name="label46.Size" type="System.Drawing.Size, System.Drawing">
+    <value>29, 13</value>
+  </data>
+  <data name="label46.TabIndex" type="System.Int32, mscorlib">
+    <value>137</value>
+  </data>
+  <data name="label46.Text" xml:space="preserve">
+    <value>Gain</value>
+  </data>
+  <data name="&gt;&gt;label46.Name" xml:space="preserve">
+    <value>label46</value>
+  </data>
+  <data name="&gt;&gt;label46.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label46.Parent" xml:space="preserve">
+    <value>groupBox3</value>
+  </data>
+  <data name="&gt;&gt;label46.ZOrder" xml:space="preserve">
+    <value>0</value>
+  </data>
+  <data name="label45.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label45.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label45.Location" type="System.Drawing.Point, System.Drawing">
+    <value>6, 19</value>
+  </data>
+  <data name="label45.Size" type="System.Drawing.Size, System.Drawing">
+    <value>40, 13</value>
+  </data>
+  <data name="label45.TabIndex" type="System.Int32, mscorlib">
+    <value>136</value>
+  </data>
+  <data name="label45.Text" xml:space="preserve">
+    <value>Enable</value>
+  </data>
+  <data name="&gt;&gt;label45.Name" xml:space="preserve">
+    <value>label45</value>
+  </data>
+  <data name="&gt;&gt;label45.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label45.Parent" xml:space="preserve">
+    <value>groupBox3</value>
+  </data>
+  <data name="&gt;&gt;label45.ZOrder" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="GYR_ENABLE.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="GYR_ENABLE.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="GYR_ENABLE.Location" type="System.Drawing.Point, System.Drawing">
+    <value>57, 19</value>
+  </data>
+  <data name="GYR_ENABLE.Size" type="System.Drawing.Size, System.Drawing">
+    <value>15, 14</value>
+  </data>
+  <data name="GYR_ENABLE.TabIndex" type="System.Int32, mscorlib">
+    <value>118</value>
+  </data>
+  <data name="&gt;&gt;GYR_ENABLE.Name" xml:space="preserve">
+    <value>GYR_ENABLE</value>
+  </data>
+  <data name="&gt;&gt;GYR_ENABLE.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;GYR_ENABLE.Parent" xml:space="preserve">
+    <value>groupBox3</value>
+  </data>
+  <data name="&gt;&gt;GYR_ENABLE.ZOrder" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="GYR_GAIN.Location" type="System.Drawing.Point, System.Drawing">
+    <value>41, 35</value>
+  </data>
+  <data name="GYR_GAIN.Size" type="System.Drawing.Size, System.Drawing">
+    <value>47, 20</value>
+  </data>
+  <data name="GYR_GAIN.TabIndex" type="System.Int32, mscorlib">
+    <value>119</value>
+  </data>
+  <data name="GYR_GAIN.Text" xml:space="preserve">
+    <value>1000</value>
+  </data>
+  <data name="&gt;&gt;GYR_GAIN.Name" xml:space="preserve">
+    <value>GYR_GAIN</value>
+  </data>
+  <data name="&gt;&gt;GYR_GAIN.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;GYR_GAIN.Parent" xml:space="preserve">
+    <value>groupBox3</value>
+  </data>
+  <data name="&gt;&gt;GYR_GAIN.ZOrder" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="groupBox3.Location" type="System.Drawing.Point, System.Drawing">
+    <value>437, 314</value>
+  </data>
+  <data name="groupBox3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>101, 63</value>
+  </data>
+  <data name="groupBox3.TabIndex" type="System.Int32, mscorlib">
+    <value>168</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Gyro</value>
+  </data>
+  <data name="&gt;&gt;groupBox3.Name" xml:space="preserve">
+    <value>groupBox3</value>
+  </data>
+  <data name="&gt;&gt;groupBox3.Type" xml:space="preserve">
+    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;groupBox3.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;groupBox3.ZOrder" xml:space="preserve">
+    <value>7</value>
+  </data>
+  <data name="BUT_HS4save.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="BUT_HS4save.Location" type="System.Drawing.Point, System.Drawing">
+    <value>483, 174</value>
+  </data>
+  <data name="BUT_HS4save.Size" type="System.Drawing.Size, System.Drawing">
+    <value>69, 23</value>
+  </data>
+  <data name="BUT_HS4save.TabIndex" type="System.Int32, mscorlib">
+    <value>167</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>Manual</value>
+  </data>
+  <data name="&gt;&gt;BUT_HS4save.Name" xml:space="preserve">
+    <value>BUT_HS4save</value>
+  </data>
+  <data name="&gt;&gt;BUT_HS4save.Type" xml:space="preserve">
+    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;BUT_HS4save.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;BUT_HS4save.ZOrder" xml:space="preserve">
+    <value>8</value>
+  </data>
+  <data name="label21.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label21.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label21.Location" type="System.Drawing.Point, System.Drawing">
+    <value>24, 28</value>
+  </data>
+  <data name="label21.Size" type="System.Drawing.Size, System.Drawing">
+    <value>26, 13</value>
+  </data>
+  <data name="label21.TabIndex" type="System.Int32, mscorlib">
+    <value>120</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>Top</value>
+  </data>
+  <data name="&gt;&gt;label21.Name" xml:space="preserve">
+    <value>label21</value>
+  </data>
+  <data name="&gt;&gt;label21.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label21.Parent" xml:space="preserve">
+    <value>groupBox1</value>
+  </data>
+  <data name="&gt;&gt;label21.ZOrder" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="COL_MIN.Enabled" type="System.Boolean, mscorlib">
+    <value>False</value>
+  </data>
+  <data name="COL_MIN.Location" type="System.Drawing.Point, System.Drawing">
+    <value>18, 173</value>
+  </data>
+  <data name="COL_MIN.Size" type="System.Drawing.Size, System.Drawing">
+    <value>43, 20</value>
+  </data>
+  <data name="COL_MIN.TabIndex" type="System.Int32, mscorlib">
+    <value>119</value>
+  </data>
+  <data name="COL_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="&gt;&gt;COL_MIN.Name" xml:space="preserve">
+    <value>COL_MIN</value>
+  </data>
+  <data name="&gt;&gt;COL_MIN.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;COL_MIN.Parent" xml:space="preserve">
+    <value>groupBox1</value>
+  </data>
+  <data name="&gt;&gt;COL_MIN.ZOrder" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="COL_MID.Enabled" type="System.Boolean, mscorlib">
+    <value>False</value>
+  </data>
+  <data name="COL_MID.Location" type="System.Drawing.Point, System.Drawing">
+    <value>17, 117</value>
+  </data>
+  <data name="COL_MID.Size" type="System.Drawing.Size, System.Drawing">
+    <value>44, 20</value>
+  </data>
+  <data name="COL_MID.TabIndex" type="System.Int32, mscorlib">
+    <value>117</value>
+  </data>
+  <data name="COL_MID.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="&gt;&gt;COL_MID.Name" xml:space="preserve">
+    <value>COL_MID</value>
+  </data>
+  <data name="&gt;&gt;COL_MID.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;COL_MID.Parent" xml:space="preserve">
+    <value>groupBox1</value>
+  </data>
+  <data name="&gt;&gt;COL_MID.ZOrder" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="COL_MAX.Enabled" type="System.Boolean, mscorlib">
+    <value>False</value>
+  </data>
+  <data name="COL_MAX.Location" type="System.Drawing.Point, System.Drawing">
+    <value>18, 45</value>
+  </data>
+  <data name="COL_MAX.Size" type="System.Drawing.Size, System.Drawing">
+    <value>43, 20</value>
+  </data>
+  <data name="COL_MAX.TabIndex" type="System.Int32, mscorlib">
+    <value>115</value>
+  </data>
+  <data name="COL_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="&gt;&gt;COL_MAX.Name" xml:space="preserve">
+    <value>COL_MAX</value>
+  </data>
+  <data name="&gt;&gt;COL_MAX.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;COL_MAX.Parent" xml:space="preserve">
+    <value>groupBox1</value>
+  </data>
+  <data name="&gt;&gt;COL_MAX.ZOrder" xml:space="preserve">
+    <value>4</value>
+  </data>
+  <data name="BUT_0collective.Enabled" type="System.Boolean, mscorlib">
+    <value>False</value>
+  </data>
+  <data name="BUT_0collective.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="BUT_0collective.Location" type="System.Drawing.Point, System.Drawing">
+    <value>11, 89</value>
+  </data>
+  <data name="BUT_0collective.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 23</value>
+  </data>
+  <data name="BUT_0collective.TabIndex" type="System.Int32, mscorlib">
+    <value>110</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>Zero</value>
+  </data>
+  <data name="&gt;&gt;BUT_0collective.Name" xml:space="preserve">
+    <value>BUT_0collective</value>
+  </data>
+  <data name="&gt;&gt;BUT_0collective.Type" xml:space="preserve">
+    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;BUT_0collective.Parent" xml:space="preserve">
+    <value>groupBox1</value>
+  </data>
+  <data name="&gt;&gt;BUT_0collective.ZOrder" xml:space="preserve">
+    <value>5</value>
+  </data>
+  <data name="groupBox1.Location" type="System.Drawing.Point, System.Drawing">
+    <value>297, 95</value>
+  </data>
+  <data name="groupBox1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>80, 209</value>
+  </data>
+  <data name="groupBox1.TabIndex" type="System.Int32, mscorlib">
+    <value>165</value>
+  </data>
+  <data name="&gt;&gt;groupBox1.Name" xml:space="preserve">
+    <value>groupBox1</value>
+  </data>
+  <data name="&gt;&gt;groupBox1.Type" xml:space="preserve">
+    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;groupBox1.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;groupBox1.ZOrder" xml:space="preserve">
+    <value>9</value>
+  </data>
+  <data name="label24.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label24.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label24.Location" type="System.Drawing.Point, System.Drawing">
+    <value>112, 23</value>
+  </data>
+  <data name="label24.Size" type="System.Drawing.Size, System.Drawing">
+    <value>27, 13</value>
+  </data>
+  <data name="label24.TabIndex" type="System.Int32, mscorlib">
+    <value>135</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>Max</value>
+  </data>
+  <data name="&gt;&gt;label24.Name" xml:space="preserve">
+    <value>label24</value>
+  </data>
+  <data name="&gt;&gt;label24.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label24.Parent" xml:space="preserve">
+    <value>groupBox2</value>
+  </data>
+  <data name="&gt;&gt;label24.ZOrder" xml:space="preserve">
+    <value>0</value>
+  </data>
+  <data name="HS4_MIN.Enabled" type="System.Boolean, mscorlib">
+    <value>False</value>
+  </data>
+  <data name="HS4_MIN.Location" type="System.Drawing.Point, System.Drawing">
+    <value>21, 40</value>
+  </data>
+  <data name="HS4_MIN.Size" type="System.Drawing.Size, System.Drawing">
+    <value>43, 20</value>
+  </data>
+  <data name="HS4_MIN.TabIndex" type="System.Int32, mscorlib">
+    <value>132</value>
+  </data>
+  <data name="HS4_MIN.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="&gt;&gt;HS4_MIN.Name" xml:space="preserve">
+    <value>HS4_MIN</value>
+  </data>
+  <data name="&gt;&gt;HS4_MIN.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;HS4_MIN.Parent" xml:space="preserve">
+    <value>groupBox2</value>
+  </data>
+  <data name="&gt;&gt;HS4_MIN.ZOrder" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="HS4_MAX.Enabled" type="System.Boolean, mscorlib">
+    <value>False</value>
+  </data>
+  <data name="HS4_MAX.Location" type="System.Drawing.Point, System.Drawing">
+    <value>106, 40</value>
+  </data>
+  <data name="HS4_MAX.Size" type="System.Drawing.Size, System.Drawing">
+    <value>43, 20</value>
+  </data>
+  <data name="HS4_MAX.TabIndex" type="System.Int32, mscorlib">
+    <value>133</value>
+  </data>
+  <data name="HS4_MAX.Text" xml:space="preserve">
+    <value>1500</value>
+  </data>
+  <data name="&gt;&gt;HS4_MAX.Name" xml:space="preserve">
+    <value>HS4_MAX</value>
+  </data>
+  <data name="&gt;&gt;HS4_MAX.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;HS4_MAX.Parent" xml:space="preserve">
+    <value>groupBox2</value>
+  </data>
+  <data name="&gt;&gt;HS4_MAX.ZOrder" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="label40.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label40.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label40.Location" type="System.Drawing.Point, System.Drawing">
+    <value>27, 23</value>
+  </data>
+  <data name="label40.Size" type="System.Drawing.Size, System.Drawing">
+    <value>24, 13</value>
+  </data>
+  <data name="label40.TabIndex" type="System.Int32, mscorlib">
+    <value>134</value>
+  </data>
+  <data name="label40.Text" xml:space="preserve">
+    <value>Min</value>
+  </data>
+  <data name="&gt;&gt;label40.Name" xml:space="preserve">
+    <value>label40</value>
+  </data>
+  <data name="&gt;&gt;label40.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label40.Parent" xml:space="preserve">
+    <value>groupBox2</value>
+  </data>
+  <data name="&gt;&gt;label40.ZOrder" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="groupBox2.Location" type="System.Drawing.Point, System.Drawing">
+    <value>437, 186</value>
+  </data>
+  <data name="groupBox2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>169, 78</value>
+  </data>
+  <data name="groupBox2.TabIndex" type="System.Int32, mscorlib">
+    <value>166</value>
+  </data>
+  <data name="&gt;&gt;groupBox2.Name" xml:space="preserve">
+    <value>groupBox2</value>
+  </data>
+  <data name="&gt;&gt;groupBox2.Type" xml:space="preserve">
+    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;groupBox2.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;groupBox2.ZOrder" xml:space="preserve">
+    <value>10</value>
+  </data>
+  <data name="HS3_TRIM.Location" type="System.Drawing.Point, System.Drawing">
+    <value>126, 314</value>
+  </data>
+  <data name="HS3_TRIM.Size" type="System.Drawing.Size, System.Drawing">
+    <value>44, 20</value>
+  </data>
+  <data name="HS3_TRIM.TabIndex" type="System.Int32, mscorlib">
+    <value>164</value>
+  </data>
+  <data name="&gt;&gt;HS3_TRIM.Name" xml:space="preserve">
+    <value>HS3_TRIM</value>
+  </data>
+  <data name="&gt;&gt;HS3_TRIM.Type" xml:space="preserve">
+    <value>System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;HS3_TRIM.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;HS3_TRIM.ZOrder" xml:space="preserve">
+    <value>11</value>
+  </data>
+  <data name="HS2_TRIM.Location" type="System.Drawing.Point, System.Drawing">
+    <value>126, 288</value>
+  </data>
+  <data name="HS2_TRIM.Size" type="System.Drawing.Size, System.Drawing">
+    <value>44, 20</value>
+  </data>
+  <data name="HS2_TRIM.TabIndex" type="System.Int32, mscorlib">
+    <value>163</value>
+  </data>
+  <data name="&gt;&gt;HS2_TRIM.Name" xml:space="preserve">
+    <value>HS2_TRIM</value>
+  </data>
+  <data name="&gt;&gt;HS2_TRIM.Type" xml:space="preserve">
+    <value>System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;HS2_TRIM.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;HS2_TRIM.ZOrder" xml:space="preserve">
+    <value>12</value>
+  </data>
+  <data name="HS1_TRIM.Location" type="System.Drawing.Point, System.Drawing">
+    <value>126, 262</value>
+  </data>
+  <data name="HS1_TRIM.Size" type="System.Drawing.Size, System.Drawing">
+    <value>44, 20</value>
+  </data>
+  <data name="HS1_TRIM.TabIndex" type="System.Int32, mscorlib">
+    <value>162</value>
+  </data>
+  <data name="&gt;&gt;HS1_TRIM.Name" xml:space="preserve">
+    <value>HS1_TRIM</value>
+  </data>
+  <data name="&gt;&gt;HS1_TRIM.Type" xml:space="preserve">
+    <value>System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;HS1_TRIM.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;HS1_TRIM.ZOrder" xml:space="preserve">
+    <value>13</value>
+  </data>
+  <data name="label39.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label39.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label39.Location" type="System.Drawing.Point, System.Drawing">
+    <value>131, 249</value>
+  </data>
+  <data name="label39.Size" type="System.Drawing.Size, System.Drawing">
+    <value>27, 13</value>
+  </data>
+  <data name="label39.TabIndex" type="System.Int32, mscorlib">
+    <value>161</value>
+  </data>
+  <data name="label39.Text" xml:space="preserve">
+    <value>Trim</value>
+  </data>
+  <data name="&gt;&gt;label39.Name" xml:space="preserve">
+    <value>label39</value>
+  </data>
+  <data name="&gt;&gt;label39.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label39.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label39.ZOrder" xml:space="preserve">
+    <value>14</value>
+  </data>
+  <data name="label38.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label38.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label38.Location" type="System.Drawing.Point, System.Drawing">
+    <value>102, 249</value>
+  </data>
+  <data name="label38.Size" type="System.Drawing.Size, System.Drawing">
+    <value>27, 13</value>
+  </data>
+  <data name="label38.TabIndex" type="System.Int32, mscorlib">
+    <value>160</value>
+  </data>
+  <data name="label38.Text" xml:space="preserve">
+    <value>Rev</value>
+  </data>
+  <data name="&gt;&gt;label38.Name" xml:space="preserve">
+    <value>label38</value>
+  </data>
+  <data name="&gt;&gt;label38.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label38.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label38.ZOrder" xml:space="preserve">
+    <value>15</value>
+  </data>
+  <data name="label37.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label37.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label37.Location" type="System.Drawing.Point, System.Drawing">
+    <value>54, 249</value>
+  </data>
+  <data name="label37.Size" type="System.Drawing.Size, System.Drawing">
+    <value>44, 13</value>
+  </data>
+  <data name="label37.TabIndex" type="System.Int32, mscorlib">
+    <value>159</value>
+  </data>
+  <data name="label37.Text" xml:space="preserve">
+    <value>Position</value>
+  </data>
+  <data name="&gt;&gt;label37.Name" xml:space="preserve">
+    <value>label37</value>
+  </data>
+  <data name="&gt;&gt;label37.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label37.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label37.ZOrder" xml:space="preserve">
+    <value>16</value>
+  </data>
+  <data name="label36.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label36.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label36.Location" type="System.Drawing.Point, System.Drawing">
+    <value>17, 249</value>
+  </data>
+  <data name="label36.Size" type="System.Drawing.Size, System.Drawing">
+    <value>35, 13</value>
+  </data>
+  <data name="label36.TabIndex" type="System.Int32, mscorlib">
+    <value>158</value>
+  </data>
+  <data name="label36.Text" xml:space="preserve">
+    <value>Servo</value>
+  </data>
+  <data name="&gt;&gt;label36.Name" xml:space="preserve">
+    <value>label36</value>
+  </data>
+  <data name="&gt;&gt;label36.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label36.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label36.ZOrder" xml:space="preserve">
+    <value>17</value>
+  </data>
+  <data name="label26.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label26.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label26.Location" type="System.Drawing.Point, System.Drawing">
+    <value>260, 365</value>
+  </data>
+  <data name="label26.Size" type="System.Drawing.Size, System.Drawing">
+    <value>54, 13</value>
+  </data>
+  <data name="label26.TabIndex" type="System.Int32, mscorlib">
+    <value>157</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>Pitch Max</value>
+  </data>
+  <data name="&gt;&gt;label26.Name" xml:space="preserve">
+    <value>label26</value>
+  </data>
+  <data name="&gt;&gt;label26.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label26.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label26.ZOrder" xml:space="preserve">
+    <value>18</value>
+  </data>
+  <data name="PIT_MAX.Location" type="System.Drawing.Point, System.Drawing">
+    <value>314, 362</value>
+  </data>
+  <data name="PIT_MAX.Size" type="System.Drawing.Size, System.Drawing">
+    <value>47, 20</value>
+  </data>
+  <data name="PIT_MAX.TabIndex" type="System.Int32, mscorlib">
+    <value>156</value>
+  </data>
+  <data name="PIT_MAX.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="&gt;&gt;PIT_MAX.Name" xml:space="preserve">
+    <value>PIT_MAX</value>
+  </data>
+  <data name="&gt;&gt;PIT_MAX.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;PIT_MAX.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;PIT_MAX.ZOrder" xml:space="preserve">
+    <value>19</value>
+  </data>
+  <data name="label25.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label25.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label25.Location" type="System.Drawing.Point, System.Drawing">
+    <value>260, 341</value>
+  </data>
+  <data name="label25.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 13</value>
+  </data>
+  <data name="label25.TabIndex" type="System.Int32, mscorlib">
+    <value>155</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>Roll Max</value>
+  </data>
+  <data name="&gt;&gt;label25.Name" xml:space="preserve">
+    <value>label25</value>
+  </data>
+  <data name="&gt;&gt;label25.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label25.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label25.ZOrder" xml:space="preserve">
+    <value>20</value>
+  </data>
+  <data name="ROL_MAX.Location" type="System.Drawing.Point, System.Drawing">
+    <value>314, 336</value>
+  </data>
+  <data name="ROL_MAX.Size" type="System.Drawing.Size, System.Drawing">
+    <value>47, 20</value>
+  </data>
+  <data name="ROL_MAX.TabIndex" type="System.Int32, mscorlib">
+    <value>154</value>
+  </data>
+  <data name="ROL_MAX.Text" xml:space="preserve">
+    <value>4500</value>
+  </data>
+  <data name="&gt;&gt;ROL_MAX.Name" xml:space="preserve">
+    <value>ROL_MAX</value>
+  </data>
+  <data name="&gt;&gt;ROL_MAX.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;ROL_MAX.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;ROL_MAX.ZOrder" xml:space="preserve">
+    <value>21</value>
+  </data>
+  <data name="label23.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label23.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label23.Location" type="System.Drawing.Point, System.Drawing">
+    <value>480, 66</value>
+  </data>
+  <data name="label23.Size" type="System.Drawing.Size, System.Drawing">
+    <value>75, 13</value>
+  </data>
+  <data name="label23.TabIndex" type="System.Int32, mscorlib">
+    <value>153</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>Rudder Travel</value>
+  </data>
+  <data name="&gt;&gt;label23.Name" xml:space="preserve">
+    <value>label23</value>
+  </data>
+  <data name="&gt;&gt;label23.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label23.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label23.ZOrder" xml:space="preserve">
+    <value>22</value>
+  </data>
+  <data name="label22.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label22.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label22.Location" type="System.Drawing.Point, System.Drawing">
+    <value>236, 66</value>
+  </data>
+  <data name="label22.Size" type="System.Drawing.Size, System.Drawing">
+    <value>72, 13</value>
+  </data>
+  <data name="label22.TabIndex" type="System.Int32, mscorlib">
+    <value>150</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>Swash Travel</value>
+  </data>
+  <data name="&gt;&gt;label22.Name" xml:space="preserve">
+    <value>label22</value>
+  </data>
+  <data name="&gt;&gt;label22.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label22.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label22.ZOrder" xml:space="preserve">
+    <value>23</value>
+  </data>
+  <data name="label20.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label20.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label20.Location" type="System.Drawing.Point, System.Drawing">
+    <value>27, 317</value>
+  </data>
+  <data name="label20.Size" type="System.Drawing.Size, System.Drawing">
+    <value>13, 13</value>
+  </data>
+  <data name="label20.TabIndex" type="System.Int32, mscorlib">
+    <value>149</value>
+  </data>
+  <data name="label20.Text" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="&gt;&gt;label20.Name" xml:space="preserve">
+    <value>label20</value>
+  </data>
+  <data name="&gt;&gt;label20.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label20.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label20.ZOrder" xml:space="preserve">
+    <value>24</value>
+  </data>
+  <data name="label19.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label19.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label19.Location" type="System.Drawing.Point, System.Drawing">
+    <value>27, 291</value>
+  </data>
+  <data name="label19.Size" type="System.Drawing.Size, System.Drawing">
+    <value>13, 13</value>
+  </data>
+  <data name="label19.TabIndex" type="System.Int32, mscorlib">
+    <value>148</value>
+  </data>
+  <data name="label19.Text" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="&gt;&gt;label19.Name" xml:space="preserve">
+    <value>label19</value>
+  </data>
+  <data name="&gt;&gt;label19.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label19.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label19.ZOrder" xml:space="preserve">
+    <value>25</value>
+  </data>
+  <data name="label18.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label18.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label18.Location" type="System.Drawing.Point, System.Drawing">
+    <value>27, 265</value>
+  </data>
+  <data name="label18.Size" type="System.Drawing.Size, System.Drawing">
+    <value>13, 13</value>
+  </data>
+  <data name="label18.TabIndex" type="System.Int32, mscorlib">
+    <value>147</value>
+  </data>
+  <data name="label18.Text" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="&gt;&gt;label18.Name" xml:space="preserve">
+    <value>label18</value>
+  </data>
+  <data name="&gt;&gt;label18.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label18.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label18.ZOrder" xml:space="preserve">
+    <value>26</value>
+  </data>
+  <data name="SV3_POS.Location" type="System.Drawing.Point, System.Drawing">
+    <value>57, 314</value>
+  </data>
+  <data name="SV3_POS.Size" type="System.Drawing.Size, System.Drawing">
+    <value>39, 20</value>
+  </data>
+  <data name="SV3_POS.TabIndex" type="System.Int32, mscorlib">
+    <value>146</value>
+  </data>
+  <data name="SV3_POS.Text" xml:space="preserve">
+    <value>180</value>
+  </data>
+  <data name="&gt;&gt;SV3_POS.Name" xml:space="preserve">
+    <value>SV3_POS</value>
+  </data>
+  <data name="&gt;&gt;SV3_POS.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;SV3_POS.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;SV3_POS.ZOrder" xml:space="preserve">
+    <value>27</value>
+  </data>
+  <data name="SV2_POS.Location" type="System.Drawing.Point, System.Drawing">
+    <value>57, 288</value>
+  </data>
+  <data name="SV2_POS.Size" type="System.Drawing.Size, System.Drawing">
+    <value>39, 20</value>
+  </data>
+  <data name="SV2_POS.TabIndex" type="System.Int32, mscorlib">
+    <value>145</value>
+  </data>
+  <data name="SV2_POS.Text" xml:space="preserve">
+    <value>60</value>
+  </data>
+  <data name="&gt;&gt;SV2_POS.Name" xml:space="preserve">
+    <value>SV2_POS</value>
+  </data>
+  <data name="&gt;&gt;SV2_POS.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;SV2_POS.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;SV2_POS.ZOrder" xml:space="preserve">
+    <value>28</value>
+  </data>
+  <data name="SV1_POS.Location" type="System.Drawing.Point, System.Drawing">
+    <value>57, 262</value>
+  </data>
+  <data name="SV1_POS.Size" type="System.Drawing.Size, System.Drawing">
+    <value>39, 20</value>
+  </data>
+  <data name="SV1_POS.TabIndex" type="System.Int32, mscorlib">
+    <value>144</value>
+  </data>
+  <data name="SV1_POS.Text" xml:space="preserve">
+    <value>-60</value>
+  </data>
+  <data name="&gt;&gt;SV1_POS.Name" xml:space="preserve">
+    <value>SV1_POS</value>
+  </data>
+  <data name="&gt;&gt;SV1_POS.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;SV1_POS.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;SV1_POS.ZOrder" xml:space="preserve">
+    <value>29</value>
+  </data>
+  <data name="HS3_REV.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="HS3_REV.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="HS3_REV.Location" type="System.Drawing.Point, System.Drawing">
+    <value>105, 317</value>
+  </data>
+  <data name="HS3_REV.Size" type="System.Drawing.Size, System.Drawing">
+    <value>15, 14</value>
+  </data>
+  <data name="HS3_REV.TabIndex" type="System.Int32, mscorlib">
+    <value>143</value>
+  </data>
+  <data name="&gt;&gt;HS3_REV.Name" xml:space="preserve">
+    <value>HS3_REV</value>
+  </data>
+  <data name="&gt;&gt;HS3_REV.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;HS3_REV.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;HS3_REV.ZOrder" xml:space="preserve">
+    <value>30</value>
+  </data>
+  <data name="HS2_REV.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="HS2_REV.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="HS2_REV.Location" type="System.Drawing.Point, System.Drawing">
+    <value>105, 291</value>
+  </data>
+  <data name="HS2_REV.Size" type="System.Drawing.Size, System.Drawing">
+    <value>15, 14</value>
+  </data>
+  <data name="HS2_REV.TabIndex" type="System.Int32, mscorlib">
+    <value>142</value>
+  </data>
+  <data name="&gt;&gt;HS2_REV.Name" xml:space="preserve">
+    <value>HS2_REV</value>
+  </data>
+  <data name="&gt;&gt;HS2_REV.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;HS2_REV.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;HS2_REV.ZOrder" xml:space="preserve">
+    <value>31</value>
+  </data>
+  <data name="HS1_REV.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="HS1_REV.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="HS1_REV.Location" type="System.Drawing.Point, System.Drawing">
+    <value>105, 268</value>
+  </data>
+  <data name="HS1_REV.Size" type="System.Drawing.Size, System.Drawing">
+    <value>15, 14</value>
+  </data>
+  <data name="HS1_REV.TabIndex" type="System.Int32, mscorlib">
+    <value>141</value>
+  </data>
+  <data name="&gt;&gt;HS1_REV.Name" xml:space="preserve">
+    <value>HS1_REV</value>
+  </data>
+  <data name="&gt;&gt;HS1_REV.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;HS1_REV.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;HS1_REV.ZOrder" xml:space="preserve">
+    <value>32</value>
+  </data>
+  <data name="label17.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label17.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label17.Location" type="System.Drawing.Point, System.Drawing">
+    <value>42, 66</value>
+  </data>
+  <data name="label17.Size" type="System.Drawing.Size, System.Drawing">
+    <value>109, 13</value>
+  </data>
+  <data name="label17.TabIndex" type="System.Int32, mscorlib">
+    <value>140</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>Swash-Servo position</value>
+  </data>
+  <data name="&gt;&gt;label17.Name" xml:space="preserve">
+    <value>label17</value>
+  </data>
+  <data name="&gt;&gt;label17.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label17.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label17.ZOrder" xml:space="preserve">
+    <value>33</value>
+  </data>
+  <metadata name="currentStateBindingSource.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
+    <value>17, 17</value>
+  </metadata>
+  <data name="HS4.Location" type="System.Drawing.Point, System.Drawing">
+    <value>396, 93</value>
+  </data>
+  <data name="HS4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>242, 42</value>
+  </data>
+  <data name="HS4.TabIndex" type="System.Int32, mscorlib">
+    <value>152</value>
+  </data>
+  <data name="&gt;&gt;HS4.Name" xml:space="preserve">
+    <value>HS4</value>
+  </data>
+  <data name="&gt;&gt;HS4.Type" xml:space="preserve">
+    <value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;HS4.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;HS4.ZOrder" xml:space="preserve">
+    <value>34</value>
+  </data>
+  <data name="HS3.Location" type="System.Drawing.Point, System.Drawing">
+    <value>239, 95</value>
+  </data>
+  <data name="HS3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>42, 213</value>
+  </data>
+  <data name="HS3.TabIndex" type="System.Int32, mscorlib">
+    <value>151</value>
+  </data>
+  <data name="&gt;&gt;HS3.Name" xml:space="preserve">
+    <value>HS3</value>
+  </data>
+  <data name="&gt;&gt;HS3.Type" xml:space="preserve">
+    <value>ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;HS3.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;HS3.ZOrder" xml:space="preserve">
+    <value>35</value>
+  </data>
+  <data name="Gservoloc.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
+    <value>Zoom</value>
+  </data>
+  <data name="Gservoloc.Font" type="System.Drawing.Font, System.Drawing">
+    <value>Microsoft Sans Serif, 9pt</value>
+  </data>
+  <data name="Gservoloc.Location" type="System.Drawing.Point, System.Drawing">
+    <value>20, 93</value>
+  </data>
+  <data name="Gservoloc.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>0, 0, 0, 0</value>
+  </data>
+  <data name="Gservoloc.Size" type="System.Drawing.Size, System.Drawing">
+    <value>150, 150</value>
+  </data>
+  <data name="Gservoloc.TabIndex" type="System.Int32, mscorlib">
+    <value>139</value>
+  </data>
+  <data name="&gt;&gt;Gservoloc.Name" xml:space="preserve">
+    <value>Gservoloc</value>
+  </data>
+  <data name="&gt;&gt;Gservoloc.Type" xml:space="preserve">
+    <value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;Gservoloc.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;Gservoloc.ZOrder" xml:space="preserve">
+    <value>36</value>
+  </data>
+  <data name="label44.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label44.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label44.Location" type="System.Drawing.Point, System.Drawing">
+    <value>529, 268</value>
+  </data>
+  <data name="label44.Size" type="System.Drawing.Size, System.Drawing">
+    <value>27, 13</value>
+  </data>
+  <data name="label44.TabIndex" type="System.Int32, mscorlib">
+    <value>174</value>
+  </data>
+  <data name="label44.Text" xml:space="preserve">
+    <value>Trim</value>
+  </data>
+  <data name="&gt;&gt;label44.Name" xml:space="preserve">
+    <value>label44</value>
+  </data>
+  <data name="&gt;&gt;label44.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label44.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label44.ZOrder" xml:space="preserve">
+    <value>0</value>
+  </data>
+  <data name="label43.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label43.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label43.Location" type="System.Drawing.Point, System.Drawing">
+    <value>496, 268</value>
+  </data>
+  <data name="label43.Size" type="System.Drawing.Size, System.Drawing">
+    <value>27, 13</value>
+  </data>
+  <data name="label43.TabIndex" type="System.Int32, mscorlib">
+    <value>173</value>
+  </data>
+  <data name="label43.Text" xml:space="preserve">
+    <value>Rev</value>
+  </data>
+  <data name="&gt;&gt;label43.Name" xml:space="preserve">
+    <value>label43</value>
+  </data>
+  <data name="&gt;&gt;label43.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label43.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label43.ZOrder" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="label42.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label42.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label42.Location" type="System.Drawing.Point, System.Drawing">
+    <value>448, 288</value>
+  </data>
+  <data name="label42.Size" type="System.Drawing.Size, System.Drawing">
+    <value>42, 13</value>
+  </data>
+  <data name="label42.TabIndex" type="System.Int32, mscorlib">
+    <value>172</value>
+  </data>
+  <data name="label42.Text" xml:space="preserve">
+    <value>Rudder</value>
+  </data>
+  <data name="&gt;&gt;label42.Name" xml:space="preserve">
+    <value>label42</value>
+  </data>
+  <data name="&gt;&gt;label42.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label42.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;label42.ZOrder" xml:space="preserve">
+    <value>2</value>
+  </data>
+  <data name="HS4_TRIM.Location" type="System.Drawing.Point, System.Drawing">
+    <value>532, 284</value>
+  </data>
+  <data name="HS4_TRIM.Size" type="System.Drawing.Size, System.Drawing">
+    <value>44, 20</value>
+  </data>
+  <data name="HS4_TRIM.TabIndex" type="System.Int32, mscorlib">
+    <value>171</value>
+  </data>
+  <data name="&gt;&gt;HS4_TRIM.Name" xml:space="preserve">
+    <value>HS4_TRIM</value>
+  </data>
+  <data name="&gt;&gt;HS4_TRIM.Type" xml:space="preserve">
+    <value>System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;HS4_TRIM.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;HS4_TRIM.ZOrder" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="HS4_REV.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="HS4_REV.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="HS4_REV.Location" type="System.Drawing.Point, System.Drawing">
+    <value>499, 287</value>
+  </data>
+  <data name="HS4_REV.Size" type="System.Drawing.Size, System.Drawing">
+    <value>15, 14</value>
+  </data>
+  <data name="HS4_REV.TabIndex" type="System.Int32, mscorlib">
+    <value>170</value>
+  </data>
+  <data name="&gt;&gt;HS4_REV.Name" xml:space="preserve">
+    <value>HS4_REV</value>
+  </data>
+  <data name="&gt;&gt;HS4_REV.Type" xml:space="preserve">
+    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;HS4_REV.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;HS4_REV.ZOrder" xml:space="preserve">
+    <value>4</value>
+  </data>
+  <metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
+    <value>True</value>
+  </metadata>
+  <data name="$this.AutoScaleDimensions" type="System.Drawing.SizeF, System.Drawing">
+    <value>6, 13</value>
+  </data>
+  <data name="$this.Size" type="System.Drawing.Size, System.Drawing">
+    <value>654, 397</value>
+  </data>
+  <data name="&gt;&gt;currentStateBindingSource.Name" xml:space="preserve">
+    <value>currentStateBindingSource</value>
+  </data>
+  <data name="&gt;&gt;currentStateBindingSource.Type" xml:space="preserve">
+    <value>System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;$this.Name" xml:space="preserve">
+    <value>ConfigTradHeli</value>
+  </data>
+  <data name="&gt;&gt;$this.Type" xml:space="preserve">
+    <value>System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.zh-Hans.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.zh-Hans.resx
new file mode 100644
index 0000000000000000000000000000000000000000..f96892c423b112b28127ad582686f33464b57c5b
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.zh-Hans.resx
@@ -0,0 +1,496 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>遥控输入</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>模式</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>硬件</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>电池</value>
+  </data>
+  <data name="tabHeli.Text" xml:space="preserve">
+    <value>AC2 直升机</value>
+  </data>
+  <data name="groupBoxElevons.Text" xml:space="preserve">
+    <value>上降副翼 (Elevon) 配置</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="CHK_elevonch2rev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>115, 17</value>
+  </data>
+  <data name="CHK_elevonch2rev.Text" xml:space="preserve">
+    <value>Elevons CH2 逆转</value>
+  </data>
+  <data name="CHK_elevonrev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>91, 17</value>
+  </data>
+  <data name="CHK_elevonrev.Text" xml:space="preserve">
+    <value>Elevons 逆转</value>
+  </data>
+  <data name="CHK_elevonch1rev.Size" type="System.Drawing.Size, System.Drawing">
+    <value>115, 17</value>
+  </data>
+  <data name="CHK_elevonch1rev.Text" xml:space="preserve">
+    <value>Elevons CH1 逆转</value>
+  </data>
+  <data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch3.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch4.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch2.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch1.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>校准遥控</value>
+  </data>
+  <data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>简单模式</value>
+  </data>
+  <data name="label14.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>当前 PWM:</value>
+  </data>
+  <data name="label13.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>当前模式:</value>
+  </data>
+  <data name="label6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>飞行模式 6</value>
+  </data>
+  <data name="label5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>飞行模式 5</value>
+  </data>
+  <data name="label4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>飞行模式 4</value>
+  </data>
+  <data name="label3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>飞行模式 3</value>
+  </data>
+  <data name="label2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>飞行模式 2</value>
+  </data>
+  <data name="label1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>飞行模式 1</value>
+  </data>
+  <data name="BUT_SaveModes.Text" xml:space="preserve">
+    <value>保存模式</value>
+  </data>
+  <data name="label27.Text" xml:space="preserve">
+    <value>十进制, 2° 3' W 就是 -2.3</value>
+  </data>
+  <data name="CHK_enableoptflow.Text" xml:space="preserve">
+    <value>启用光流</value>
+  </data>
+  <data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
+    <value>67, 13</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>磁偏角网站</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>磁偏角</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>启用空速计</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>启用声纳</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>启用罗盘</value>
+  </data>
+  <data name="label31.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label31.Text" xml:space="preserve">
+    <value>输入电压:</value>
+  </data>
+  <data name="label32.Size" type="System.Drawing.Size, System.Drawing">
+    <value>94, 13</value>
+  </data>
+  <data name="label32.Text" xml:space="preserve">
+    <value>测量的电池电压:</value>
+  </data>
+  <data name="label33.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label33.Text" xml:space="preserve">
+    <value>电池电压:</value>
+  </data>
+  <data name="label34.Size" type="System.Drawing.Size, System.Drawing">
+    <value>52, 13</value>
+  </data>
+  <data name="label34.Text" xml:space="preserve">
+    <value>分 压 比:</value>
+  </data>
+  <data name="label35.Size" type="System.Drawing.Size, System.Drawing">
+    <value>63, 13</value>
+  </data>
+  <data name="label35.Text" xml:space="preserve">
+    <value>安培/伏特:</value>
+  </data>
+  <data name="label47.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 18</value>
+  </data>
+  <data name="label47.Text" xml:space="preserve">
+    <value>传感器</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>电压传感器校准:
+1. 测量APM输入电压,输入到下方的文本框中
+2. 测量电池电压,输入到下方的文本框中
+3. 从当前的传感器的数据表中找到安培/伏特,输入到下方的文本框中</value>
+  </data>
+  <data name="label29.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>容量</value>
+  </data>
+  <data name="label30.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 13</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>监控器</value>
+  </data>
+  <data name="label28.Size" type="System.Drawing.Size, System.Drawing">
+    <value>175, 13</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>设置水平面的默认加速度计偏移</value>
+  </data>
+  <data name="label16.Size" type="System.Drawing.Size, System.Drawing">
+    <value>261, 13</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>注: 图片只是用于展示,设置可以用于六轴等机架</value>
+  </data>
+  <data name="label15.Size" type="System.Drawing.Size, System.Drawing">
+    <value>93, 13</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>机架设置 (+ 或 x)</value>
+  </data>
+  <data name="BUT_levelac2.Text" xml:space="preserve">
+    <value>找平</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>手动</value>
+  </data>
+  <data name="BUT_swash_manual.Text" xml:space="preserve">
+    <value>手动</value>
+  </data>
+  <data name="label46.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label46.Text" xml:space="preserve">
+    <value>感度</value>
+  </data>
+  <data name="label45.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label45.Text" xml:space="preserve">
+    <value>启用</value>
+  </data>
+  <data name="label44.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label44.Text" xml:space="preserve">
+    <value>微调</value>
+  </data>
+  <data name="label43.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label43.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="label42.Size" type="System.Drawing.Size, System.Drawing">
+    <value>43, 13</value>
+  </data>
+  <data name="label42.Text" xml:space="preserve">
+    <value>方向舵</value>
+  </data>
+  <data name="label24.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>最大</value>
+  </data>
+  <data name="label40.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label40.Text" xml:space="preserve">
+    <value>最小</value>
+  </data>
+  <data name="label41.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label41.Text" xml:space="preserve">
+    <value>最低</value>
+  </data>
+  <data name="label21.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>最高</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>0度</value>
+  </data>
+  <data name="label39.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label39.Text" xml:space="preserve">
+    <value>微调</value>
+  </data>
+  <data name="label38.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label38.Text" xml:space="preserve">
+    <value>逆转</value>
+  </data>
+  <data name="label37.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label37.Text" xml:space="preserve">
+    <value>位置</value>
+  </data>
+  <data name="label36.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label36.Text" xml:space="preserve">
+    <value>舵机</value>
+  </data>
+  <data name="label26.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>最大俯仰</value>
+  </data>
+  <data name="label25.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>最大侧倾</value>
+  </data>
+  <data name="label23.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>舵机行程</value>
+  </data>
+  <data name="label22.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>斜盘水平微调</value>
+  </data>
+  <data name="label17.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>斜盘舵机位置</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>重置</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>重置 APM 为默认设置</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APM设置</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.zh-TW.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.zh-TW.resx
new file mode 100644
index 0000000000000000000000000000000000000000..0c03fbf8ed6bd5befc34246175bf1adf106cce43
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.zh-TW.resx
@@ -0,0 +1,460 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>重置</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>遙控輸入</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>模式</value>
+  </data>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>硬件</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>電池</value>
+  </data>
+  <data name="BUT_reset.Text" xml:space="preserve">
+    <value>重置 APM 為默認設置</value>
+  </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch3.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch4.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch2.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>50, 17</value>
+  </data>
+  <data name="CHK_revch1.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="BUT_Calibrateradio.Text" xml:space="preserve">
+    <value>校準遙控</value>
+  </data>
+  <data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple6.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple5.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple4.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple3.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple2.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>74, 17</value>
+  </data>
+  <data name="CB_simple1.Text" xml:space="preserve">
+    <value>簡單模式</value>
+  </data>
+  <data name="label14.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label14.Text" xml:space="preserve">
+    <value>當前 PWM:</value>
+  </data>
+  <data name="label13.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label13.Text" xml:space="preserve">
+    <value>當前模式:</value>
+  </data>
+  <data name="label6.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label6.Text" xml:space="preserve">
+    <value>飛行模式 6</value>
+  </data>
+  <data name="label5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label5.Text" xml:space="preserve">
+    <value>飛行模式 5</value>
+  </data>
+  <data name="label4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label4.Text" xml:space="preserve">
+    <value>飛行模式 4</value>
+  </data>
+  <data name="label3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label3.Text" xml:space="preserve">
+    <value>飛行模式 3</value>
+  </data>
+  <data name="label2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label2.Text" xml:space="preserve">
+    <value>飛行模式 2</value>
+  </data>
+  <data name="label1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>64, 13</value>
+  </data>
+  <data name="label1.Text" xml:space="preserve">
+    <value>飛行模式 1</value>
+  </data>
+  <data name="BUT_SaveModes.Text" xml:space="preserve">
+    <value>保存模式</value>
+  </data>
+  <data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
+    <value>67, 13</value>
+  </data>
+  <data name="linkLabelmagdec.Text" xml:space="preserve">
+    <value>磁偏角網站</value>
+  </data>
+  <data name="label100.Text" xml:space="preserve">
+    <value>磁偏角</value>
+  </data>
+  <data name="CHK_enableairspeed.Text" xml:space="preserve">
+    <value>啟用空速計</value>
+  </data>
+  <data name="CHK_enablesonar.Text" xml:space="preserve">
+    <value>啟用聲納</value>
+  </data>
+  <data name="CHK_enablecompass.Text" xml:space="preserve">
+    <value>啟用羅盤</value>
+  </data>
+  <data name="label35.Size" type="System.Drawing.Size, System.Drawing">
+    <value>63, 13</value>
+  </data>
+  <data name="label35.Text" xml:space="preserve">
+    <value>安培/伏特:</value>
+  </data>
+  <data name="label34.Size" type="System.Drawing.Size, System.Drawing">
+    <value>52, 13</value>
+  </data>
+  <data name="label34.Text" xml:space="preserve">
+    <value>分 壓 比:</value>
+  </data>
+  <data name="label33.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label33.Text" xml:space="preserve">
+    <value>電池電壓:</value>
+  </data>
+  <data name="label32.Size" type="System.Drawing.Size, System.Drawing">
+    <value>94, 13</value>
+  </data>
+  <data name="label32.Text" xml:space="preserve">
+    <value>測量的電池電壓:</value>
+  </data>
+  <data name="label31.Size" type="System.Drawing.Size, System.Drawing">
+    <value>58, 13</value>
+  </data>
+  <data name="label31.Text" xml:space="preserve">
+    <value>輸入電壓:</value>
+  </data>
+  <data name="textBox3.Text" xml:space="preserve">
+    <value>電壓傳感器校準:
+1. 測量APM輸入電壓,輸入到下方的文本框中
+2. 測量電池電壓,輸入到下方的文本框中
+3. 從當前的傳感器的數據表中找到安培/伏特,輸入到下方的文本框中</value>
+  </data>
+  <data name="label29.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label29.Text" xml:space="preserve">
+    <value>容量</value>
+  </data>
+  <data name="label30.Size" type="System.Drawing.Size, System.Drawing">
+    <value>48, 13</value>
+  </data>
+  <data name="label30.Text" xml:space="preserve">
+    <value>監控器</value>
+  </data>
+  <data name="label28.Size" type="System.Drawing.Size, System.Drawing">
+    <value>175, 13</value>
+  </data>
+  <data name="label28.Text" xml:space="preserve">
+    <value>設置水平面的默認加速度計偏移</value>
+  </data>
+  <data name="label16.Size" type="System.Drawing.Size, System.Drawing">
+    <value>261, 13</value>
+  </data>
+  <data name="label16.Text" xml:space="preserve">
+    <value>注: 圖片只是用於展示,設置可以用於六軸等機架</value>
+  </data>
+  <data name="label15.Size" type="System.Drawing.Size, System.Drawing">
+    <value>93, 13</value>
+  </data>
+  <data name="label15.Text" xml:space="preserve">
+    <value>機架設置 (+ 或 x)</value>
+  </data>
+  <data name="BUT_levelac2.Text" xml:space="preserve">
+    <value>找平</value>
+  </data>
+  <data name="label46.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label46.Text" xml:space="preserve">
+    <value>感度</value>
+  </data>
+  <data name="label45.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label45.Text" xml:space="preserve">
+    <value>啟用</value>
+  </data>
+  <data name="label44.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label44.Text" xml:space="preserve">
+    <value>微調</value>
+  </data>
+  <data name="label43.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label43.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="label42.Size" type="System.Drawing.Size, System.Drawing">
+    <value>43, 13</value>
+  </data>
+  <data name="label42.Text" xml:space="preserve">
+    <value>方向舵</value>
+  </data>
+  <data name="BUT_HS4save.Text" xml:space="preserve">
+    <value>手動</value>
+  </data>
+  <data name="label24.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label24.Text" xml:space="preserve">
+    <value>最大</value>
+  </data>
+  <data name="label40.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label40.Text" xml:space="preserve">
+    <value>最小</value>
+  </data>
+  <data name="BUT_swash_manual.Text" xml:space="preserve">
+    <value>手動</value>
+  </data>
+  <data name="label41.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label41.Text" xml:space="preserve">
+    <value>最低</value>
+  </data>
+  <data name="label21.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label21.Text" xml:space="preserve">
+    <value>最高</value>
+  </data>
+  <data name="BUT_0collective.Text" xml:space="preserve">
+    <value>0度</value>
+  </data>
+  <data name="label39.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label39.Text" xml:space="preserve">
+    <value>微調</value>
+  </data>
+  <data name="label38.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label38.Text" xml:space="preserve">
+    <value>逆轉</value>
+  </data>
+  <data name="label37.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label37.Text" xml:space="preserve">
+    <value>位置</value>
+  </data>
+  <data name="label36.Size" type="System.Drawing.Size, System.Drawing">
+    <value>31, 13</value>
+  </data>
+  <data name="label36.Text" xml:space="preserve">
+    <value>舵機</value>
+  </data>
+  <data name="label26.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label26.Text" xml:space="preserve">
+    <value>最大俯仰</value>
+  </data>
+  <data name="label25.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label25.Text" xml:space="preserve">
+    <value>最大側傾</value>
+  </data>
+  <data name="label23.Size" type="System.Drawing.Size, System.Drawing">
+    <value>55, 13</value>
+  </data>
+  <data name="label23.Text" xml:space="preserve">
+    <value>舵機行程</value>
+  </data>
+  <data name="label22.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label22.Text" xml:space="preserve">
+    <value>斜盤水平微調</value>
+  </data>
+  <data name="label17.Size" type="System.Drawing.Size, System.Drawing">
+    <value>79, 13</value>
+  </data>
+  <data name="label17.Text" xml:space="preserve">
+    <value>斜盤舵機位置</value>
+  </data>
+  <data name="$this.Text" xml:space="preserve">
+    <value>APM設置</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.Designer.cs
new file mode 100644
index 0000000000000000000000000000000000000000..9878d6c5428b9041c1697057687a764493f0395c
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.Designer.cs
@@ -0,0 +1,60 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    partial class Configuration
+    {
+        /// <summary> 
+        /// Required designer variable.
+        /// </summary>
+        private System.ComponentModel.IContainer components = null;
+
+        /// <summary> 
+        /// Clean up any resources being used.
+        /// </summary>
+        /// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
+        protected override void Dispose(bool disposing)
+        {
+            if (disposing && (components != null))
+            {
+                components.Dispose();
+            }
+            base.Dispose(disposing);
+        }
+
+        #region Component Designer generated code
+
+        /// <summary> 
+        /// Required method for Designer support - do not modify 
+        /// the contents of this method with the code editor.
+        /// </summary>
+        private void InitializeComponent()
+        {
+            System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Configuration));
+            this.backstageView = new ArdupilotMega.Controls.BackstageView.BackstageView();
+            this.SuspendLayout();
+            // 
+            // backstageView
+            // 
+            this.backstageView.AutoSize = true;
+            this.backstageView.Dock = System.Windows.Forms.DockStyle.Fill;
+            this.backstageView.Location = new System.Drawing.Point(0, 0);
+            this.backstageView.Name = "backstageView";
+            this.backstageView.Size = new System.Drawing.Size(634, 336);
+            this.backstageView.TabIndex = 0;
+            // 
+            // Configuration
+            // 
+            this.ClientSize = new System.Drawing.Size(634, 336);
+            this.Controls.Add(this.backstageView);
+            this.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
+            this.Name = "Configuration";
+            this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.Configuration_FormClosing);
+            this.ResumeLayout(false);
+            this.PerformLayout();
+
+        }
+
+        #endregion
+
+        private Controls.BackstageView.BackstageView backstageView;
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.cs
new file mode 100644
index 0000000000000000000000000000000000000000..459bf45cb6fa3068aa831990b68b6bb7cbe3a296
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.cs
@@ -0,0 +1,36 @@
+using System;
+using System.Collections.Generic;
+using System.ComponentModel;
+using System.Drawing;
+using System.Data;
+using System.Linq;
+using System.Text;
+using System.Windows.Forms;
+using ArdupilotMega.Controls.BackstageView;
+
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    public partial class Configuration : Form
+    {
+        public Configuration()
+        {
+            InitializeComponent();
+
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigRadioInput(), "Radio Calibration"));
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigFlightModes(), "Flight Modes"));
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigHardwareOptions(), "Hardware Options"));
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigBatteryMonitoring(), "Battery Monitor"));
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigAccelerometerCalibration(), "Level Calibration"));
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigArducopter(), "Arducopter Setup"));
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigArduplane(), "Arduplane Setup"));
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigTradHeli(), "Heli Setup"));
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigRawParams(), "Raw params (Advanced)"));
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigPlanner(), "Planner"));
+        }
+
+        private void Configuration_FormClosing(object sender, FormClosingEventArgs e)
+        {
+            backstageView.Close();
+        }
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.resx
new file mode 100644
index 0000000000000000000000000000000000000000..222a74addff376f7a18256f55e7d4028cc9a5826
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.resx
@@ -0,0 +1,197 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="$this.Icon" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+    <value>
+        AAABAAEAICAAAAEAIACoEAAAFgAAACgAAAAgAAAAQAAAAAEAIAAAAAAAABAAABILAAASCwAAAAAAAAAA
+        AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADOxkjAtnoOAKpJ4vyiK
+        c+8nh3D/J4Zv/yeHcP8oi3PvKpJ4vy6fg4AzsZIwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
+        AAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADjGo2AyspPfLZ+D/yiQ
+        d/8hlXj/G6F9/xeqg/8XqYL/GKqD/xuhfv8ilnn/KZB3/y2fhP8yspPfN8ajYAAAAAAAAAAAAAAAAAAA
+        AAAAAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADvRrDA1vpzfL6uN/yel
+        hP8XvJD/DMyY/wfQl/8FzJP/A8qS/wPJkf8EypL/BsyU/wnRmP8PzZn/Gb2R/yemhP8tqoz/Mb2a3zbQ
+        qkAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAA4y6ZgMbWV/yin
+        iP8WwZP/Btqf/wDPlf8AyI7/A8aP/yfNnv9T2LP/UNax/03XsP8506b/G8ya/wHKkf8F0Zf/CNuf/xLB
+        kv8fpYT/J7KQ/y7IomAAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAANcajny+w
+        kf8hqoj/CNSd/wDRlf8Axor/Hcyd/3Lhwf+p7Nj/o+vV/57m0/+X5dD/k+TN/4/jzf+K5Mz/fuHH/0PW
+        rf8HzJT/ANCT/wDRlv8OpX//HayI/yrFn58AAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAADDC
+        nmAtro7/H62J/wPWmv8Ay47/AMaO/3XhxP+e6tT/mObP/5Pjy/+Q4sr/jODJ/4ffx/+C3MT/f9vC/3nb
+        wf9y2r7/adq7/2DauP8ZzZv/Fdae/8T/9/9WxKj/HKuI/y7IomAAAAAAAAAAAAAAAAD///8AAAAAAAAA
+        AAAiuZMwKKyM/x6ohf8C1Zr/AMmL/wHGjv+49OL///////////9+3ML/f9zD/4Dcwv9+28L/e9rA/3bZ
+        vv9w1rr/Z9S4/17Rs/9Qz63/Qcyn/3LewP////////////n///8MpH7/JbKP/zXQqUAAAAAAAAAAAP//
+        /wAAAAAAAAAAABymhN8dnn//BNGa/wDKjP8AxY3/sfHf/////////////////2nXt/9w1rv/c9e8/3TX
+        vP9x17z/a9W5/2TTtf9Y0K//SMyp/zXFoP9i07X/////////////////f/LR/wDQlf8epYT/Mb2a3wAA
+        AAAAAAAA////AAAAAAADlnJgFZR1/wq4iv8AzpH/AMCD/4rmzf//////////////////////WdGv/2PU
+        tf9p1rf/atS4/2nUtv9i0rT/Vc+u/0fKpv8zxZz/Ws+w//////////////////////8GyJL/ANCS/xLB
+        kv8tq4z/OMajYAAAAAD///8AAAAAAACHZt8NkW//ANKV/wDChP9i27r//////////////////////9Dx
+        6P9MzKn/Vc+v/17Rsv9g0rP/XNCx/1XNrv9Fyaf/McSd/1fPr///////////////////////QM2m/ynK
+        oP8JzJX/C9yh/ymmhf80spPfAAAAAP///wAAcUwwAHtc/wCrfP8AyIv/AMKK////////////////////
+        /////////////5Dgyv9Gyqb/TMyq/07Nq/9MzKn/Qcmj/y/Fnf9Wzq3//////////////////////57k
+        0v8av5T/Lceg/yzOo/8M05v/Hr6T/zCghf80spIw////AABoRYAAclT/AL2H/wDBhf9R1rL/////////
+        ////////4vfw//////////////////H8+P9KzKn/Ocah/zTFnv8qwpj/Us2t////////////////////
+        ////////DLqM/yDBlv8wxp//OM6m/xPPm/8Xz53/LZF5/y+fg4////8AAGNAvwB7Wf8Aw4j/ALyC/4bj
+        yP+g5tL/g93E/2HSsv9Pzqz/Us6s//////////////////////9Yzq//Gr2S/0jLp///////////////
+        /////////////yrDm/8SvI//JMGY/zDHn/81zKT/Is2e/xTUnf8nl3v/LJJ5v////wAAXz3vAIlg/wDA
+        hf8AuoD/quzZ/5Hjyv9628D/ada2/1jRsP9Jy6f/a9a4//////////////////////+Y4s7/////////
+        //////////////////+c4tD/AbaH/xW8kf8jwZj/LcWd/y/Jn/8kzJ3/E9Ca/yGjgf8ri3Tv////AABd
+        PP8Ak2b/AL6D/w/Ekv+m6tf/j+HJ/3vawP9p1rf/W9Gx/0rNqf85yJ//Nsaf////////////////////
+        /////////////////////////////wCwe/8AtoT/ELqP/xu+k/8jwZj/KMeb/yHKm/8QzZf/HqyG/ymI
+        cf////8AAF07/wCSZP8AvYL/GMWU/6Dn1P+K38f/ddi+/27Wuf+E3MX/leHN/6fm1f+l5tX/neLQ////
+        ////////////////////////////////////////j9/J/27Vuv9Tzq7/JsKY/xa/kv8aw5T/FcaW/wvL
+        lf8aqoT/J4dw/////wAAXTv/AJFk/wC9gP8GwY3/mObQ/5rkz/+26dv/y/Hl/8Dt3/+06tz/pebV/5bg
+        zP+g5NL//////////////v///f7+//7+/v//////7fn2////////////tOnb/6Ll0v+v6Nj/jeDI/zXK
+        o/8IxJD/BMqS/xaqgv8lh2//////AABeO+8AgVf/AL1//wDBif/R9uv/1PPq/8Tv5P+36t3/rujY/6Lk
+        0v+U4cv/jt7J//j8+///////+/38//f8+//2+/r/+Pz7//3+/v/m9/P/9Pv6//D6+P9/28L/jd7J/5jj
+        z/+h5dL/qOvX/4Hmyf8f1J//E596/yOJcO////8AAGA8vwB3U/8p06P/hufM/8Ty5f/D7+T/s+vb/6bm
+        1P+c4c//j9/K/4vcyP/t+fb///7///j8/P/0+/r/8vr5//P7+f/1+/r/+/39///////i9fL/ZNO1/3HW
+        vP992sH/htzG/4vhyv+S5dD/mO7W/6X74v80noT/Io90v////wAAZkCAAHla/33ny/945cb/nunV/7Xr
+        3v+l5tT/luDN/4ndxv992cL/1vLq//v9/P/1+/n/8vv4//L69//z+/j/9Pv5/7Xo2//x+vn/////////
+        //+y59n/aNS3/3LWvP932r//fNzD/4Ljyf+J7ND/l/bd/yORdf8knH6A////AABuRzAAdlT/Xc6x/23o
+        xv9s4MH/qurZ/5jiz/+I3cb/edjA/8ju5f/3/Pv/8vv4//H6+P/y+/j/6/f0/7np3v/7/fz//v7+/6fk
+        1f+56tz///////////9h0bT/aNW4/23Wu/9v3L//dOLG/37w0f9m1rn/Hpt8/ymujTD///8AAAAAAACD
+        X98po4X/Z+7K/1vgvP+A4sf/jOHK/3rZwv+r59f/9Pv6/+/69//v+vf/8vr4/9fy6/9n0rf/VM6t/6Di
+        0v/N7+f/adO4/1PMrf9t1Lr/i9zI/1/Rs/9h0rX/ZNe4/2bbvf9s5sb/ePfV/z2ylf8lrozfAAAAAP//
+        /wAAAAAAAJNsYAWQbf9U1rP/Vee//0rYsf993sb/pebV//P7+v/s+Pb/6/f1/+749v+s5tj/Vc2u/1jP
+        r/9ZzrD/btW5/1bOr/9Wza//Vs6v/1fOr/9Z0LD/WdCy/1vTtP9d1rX/Xt+8/2btyP9k4L//IaaF/y7D
+        nmAAAAAA////AAAAAAAAAAAAD6J9zyCjgv9S68L/P9+0/2Pevv/5////7/v6/+v59//j9/L/gtvF/1PN
+        r/9Wz7D/Wc+x/1nQsf9Zz7H/WM6w/1fPsP9UzrD/VM+w/1TPrv9U0a//U9Oy/1Tatv9Z5sD/Y/LL/zSx
+        lP8qupbPAAAAAAAAAAD///8AAAAAAAAAAAAYto4wGaeE/y23lP8+5rn/6/////j////w//3/ve/i/2bV
+        uP9Tzq7/Vc+v/1jPsP9Z0LL/WM+w/1fOsf9Wz7D/Us2w/1HOrf9Qzq3/T9Cu/0zSr/9M2LP/TeC5/1bt
+        xP9HxaX/KLKQ/zTPqDAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAkvpdgG6iF/y++m//e/////P///3rl
+        yf9G0K3/VdKy/1bPsf9Wz7H/Vs6w/1bPsP9Sza//Ucyu/0/Nrf9NzKz/S82s/0fOrP9G0a7/QdWv/0Le
+        tP9I6L7/Q8Ok/yitjP8yyKJgAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAmwJlgG6iF/yK3
+        kP8k3q7/H9el/x7Pn/8tzKT/Q9Cs/1HQsP9Q0K7/TM6u/0nMrf9Hzaz/RMyp/0LNqf8+zqn/ONGo/zTV
+        qf833rD/O+S4/zvCof8orIv/MMSfYAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAA
+        AAAkvpdgG6iE/xukgv8gy53/HNql/xzRn/8czJz/HcmZ/yXJnP8qyp7/Lcqg/yzLn/8nypz/JMqc/yTO
+        n/8l1KT/KN2r/y3Tpv8nq4n/JaqJ/yzAm2AAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAA
+        AAAAAAAAAAAAAAAAAAAato8wFKN/zxCScv8RnHn/DbqM/wjIlP8GyZT/BsaS/wbFkf8GxZH/B8WR/wfH
+        k/8IypX/DMmV/xG3jP8WoX3/Fph2/xqkgs8ft5EwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA////AAAA
+        AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJVvYACGZM8Aelr/AHlZ/wCFX/8AiWL/AJlr/wCb
+        bP8AlGf/AI5k/wB/W/8AeFj/AHtb/wCHZd8ClXBgAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
+        AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAABwSzAAaESAAGI/vwBf
+        Pd8AXTz/AF08/wBdPP8AXz3fAGJAvwBoRIAAcUswAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
+        AAAAAAAAAAAAAP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
+        /wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
+        /wD///8A////AP///wD///8A/+AD//+AAP/+AAA//AAAH/gAAA/wAAAH4AAAA+AAAAPAAAABwAAAAYAA
+        AACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAwAAAAcAAAAHgAAAD4AAAA/AA
+        AAf4AAAP/AAAH/4AAD//gAD//+AD//////8=
+</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.Designer.cs
new file mode 100644
index 0000000000000000000000000000000000000000..6476469624b5b2a94181748a76331854cd9b7274
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.Designer.cs
@@ -0,0 +1,63 @@
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    partial class Setup
+    {
+        /// <summary> 
+        /// Required designer variable.
+        /// </summary>
+        private System.ComponentModel.IContainer components = null;
+
+        /// <summary> 
+        /// Clean up any resources being used.
+        /// </summary>
+        /// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
+        protected override void Dispose(bool disposing)
+        {
+            if (disposing && (components != null))
+            {
+                components.Dispose();
+            }
+            base.Dispose(disposing);
+        }
+
+        #region Component Designer generated code
+
+        /// <summary> 
+        /// Required method for Designer support - do not modify 
+        /// the contents of this method with the code editor.
+        /// </summary>
+        private void InitializeComponent()
+        {
+            System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Setup));
+            this.backstageView = new ArdupilotMega.Controls.BackstageView.BackstageView();
+            this.SuspendLayout();
+            // 
+            // backstageView
+            // 
+            this.backstageView.AutoSize = true;
+            this.backstageView.Dock = System.Windows.Forms.DockStyle.Fill;
+            this.backstageView.Location = new System.Drawing.Point(0, 0);
+            this.backstageView.Name = "backstageView";
+            this.backstageView.Size = new System.Drawing.Size(823, 468);
+            this.backstageView.TabIndex = 0;
+            // 
+            // Setup
+            // 
+            this.ClientSize = new System.Drawing.Size(823, 468);
+            this.Controls.Add(this.backstageView);
+            this.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
+            this.MinimumSize = new System.Drawing.Size(839, 506);
+            this.Name = "Setup";
+            this.Text = "Setup";
+            this.FormClosing += new System.Windows.Forms.FormClosingEventHandler(this.Setup_FormClosing);
+            this.Load += new System.EventHandler(this.Setup_Load);
+            this.ResumeLayout(false);
+            this.PerformLayout();
+
+        }
+
+        #endregion
+
+        private Controls.BackstageView.BackstageView backstageView;
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs
new file mode 100644
index 0000000000000000000000000000000000000000..14d1887d773bff4482dc15038a10367ed2d33409
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs
@@ -0,0 +1,43 @@
+using System;
+using System.Collections.Generic;
+using System.ComponentModel;
+using System.Drawing;
+using System.Data;
+using System.Linq;
+using System.Text;
+using System.Windows.Forms;
+using ArdupilotMega.Controls.BackstageView;
+
+namespace ArdupilotMega.GCSViews.ConfigurationView
+{
+    public partial class Setup : Form
+    {
+        public Setup()
+        {
+            InitializeComponent();
+
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigRadioInput(), "Radio Calibration"));
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigFlightModes(), "Flight Modes"));
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigHardwareOptions(), "Hardware Options"));
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigBatteryMonitoring(), "Battery Monitor"));
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigAccelerometerCalibration(), "Level Calibration"));
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigTradHeli(), "Heli Setup"));
+
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ArdupilotMega._3DRradio(), "3DR Radio"));
+
+            this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ArdupilotMega.Antenna.Tracker(), "Antenna Tracker"));
+
+            this.backstageView.ActivatePage(backstageView.Pages[0]);
+        }
+
+        private void Setup_Load(object sender, EventArgs e)
+        {
+
+        }
+
+        private void Setup_FormClosing(object sender, FormClosingEventArgs e)
+        {
+            backstageView.Close();
+        }
+    }
+}
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.resx
new file mode 100644
index 0000000000000000000000000000000000000000..222a74addff376f7a18256f55e7d4028cc9a5826
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.resx
@@ -0,0 +1,197 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+  <!-- 
+    Microsoft ResX Schema 
+    
+    Version 2.0
+    
+    The primary goals of this format is to allow a simple XML format 
+    that is mostly human readable. The generation and parsing of the 
+    various data types are done through the TypeConverter classes 
+    associated with the data types.
+    
+    Example:
+    
+    ... ado.net/XML headers & schema ...
+    <resheader name="resmimetype">text/microsoft-resx</resheader>
+    <resheader name="version">2.0</resheader>
+    <resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+    <resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+    <data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
+    <data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+    <data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+        <value>[base64 mime encoded serialized .NET Framework object]</value>
+    </data>
+    <data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+        <value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
+        <comment>This is a comment</comment>
+    </data>
+                
+    There are any number of "resheader" rows that contain simple 
+    name/value pairs.
+    
+    Each data row contains a name, and value. The row also contains a 
+    type or mimetype. Type corresponds to a .NET class that support 
+    text/value conversion through the TypeConverter architecture. 
+    Classes that don't support this are serialized and stored with the 
+    mimetype set.
+    
+    The mimetype is used for serialized objects, and tells the 
+    ResXResourceReader how to depersist the object. This is currently not 
+    extensible. For a given mimetype the value must be set accordingly:
+    
+    Note - application/x-microsoft.net.object.binary.base64 is the format 
+    that the ResXResourceWriter will generate, however the reader can 
+    read any of the formats listed below.
+    
+    mimetype: application/x-microsoft.net.object.binary.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
+            : and then encoded with base64 encoding.
+    
+    mimetype: application/x-microsoft.net.object.soap.base64
+    value   : The object must be serialized with 
+            : System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+            : and then encoded with base64 encoding.
+
+    mimetype: application/x-microsoft.net.object.bytearray.base64
+    value   : The object must be serialized into a byte array 
+            : using a System.ComponentModel.TypeConverter
+            : and then encoded with base64 encoding.
+    -->
+  <xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+    <xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
+    <xsd:element name="root" msdata:IsDataSet="true">
+      <xsd:complexType>
+        <xsd:choice maxOccurs="unbounded">
+          <xsd:element name="metadata">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" />
+              </xsd:sequence>
+              <xsd:attribute name="name" use="required" type="xsd:string" />
+              <xsd:attribute name="type" type="xsd:string" />
+              <xsd:attribute name="mimetype" type="xsd:string" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="assembly">
+            <xsd:complexType>
+              <xsd:attribute name="alias" type="xsd:string" />
+              <xsd:attribute name="name" type="xsd:string" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="data">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+                <xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
+              <xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+              <xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+              <xsd:attribute ref="xml:space" />
+            </xsd:complexType>
+          </xsd:element>
+          <xsd:element name="resheader">
+            <xsd:complexType>
+              <xsd:sequence>
+                <xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+              </xsd:sequence>
+              <xsd:attribute name="name" type="xsd:string" use="required" />
+            </xsd:complexType>
+          </xsd:element>
+        </xsd:choice>
+      </xsd:complexType>
+    </xsd:element>
+  </xsd:schema>
+  <resheader name="resmimetype">
+    <value>text/microsoft-resx</value>
+  </resheader>
+  <resheader name="version">
+    <value>2.0</value>
+  </resheader>
+  <resheader name="reader">
+    <value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <resheader name="writer">
+    <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </resheader>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
+  <data name="$this.Icon" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+    <value>
+        AAABAAEAICAAAAEAIACoEAAAFgAAACgAAAAgAAAAQAAAAAEAIAAAAAAAABAAABILAAASCwAAAAAAAAAA
+        AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADOxkjAtnoOAKpJ4vyiK
+        c+8nh3D/J4Zv/yeHcP8oi3PvKpJ4vy6fg4AzsZIwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
+        AAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADjGo2AyspPfLZ+D/yiQ
+        d/8hlXj/G6F9/xeqg/8XqYL/GKqD/xuhfv8ilnn/KZB3/y2fhP8yspPfN8ajYAAAAAAAAAAAAAAAAAAA
+        AAAAAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADvRrDA1vpzfL6uN/yel
+        hP8XvJD/DMyY/wfQl/8FzJP/A8qS/wPJkf8EypL/BsyU/wnRmP8PzZn/Gb2R/yemhP8tqoz/Mb2a3zbQ
+        qkAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAA4y6ZgMbWV/yin
+        iP8WwZP/Btqf/wDPlf8AyI7/A8aP/yfNnv9T2LP/UNax/03XsP8506b/G8ya/wHKkf8F0Zf/CNuf/xLB
+        kv8fpYT/J7KQ/y7IomAAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAANcajny+w
+        kf8hqoj/CNSd/wDRlf8Axor/Hcyd/3Lhwf+p7Nj/o+vV/57m0/+X5dD/k+TN/4/jzf+K5Mz/fuHH/0PW
+        rf8HzJT/ANCT/wDRlv8OpX//HayI/yrFn58AAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAADDC
+        nmAtro7/H62J/wPWmv8Ay47/AMaO/3XhxP+e6tT/mObP/5Pjy/+Q4sr/jODJ/4ffx/+C3MT/f9vC/3nb
+        wf9y2r7/adq7/2DauP8ZzZv/Fdae/8T/9/9WxKj/HKuI/y7IomAAAAAAAAAAAAAAAAD///8AAAAAAAAA
+        AAAiuZMwKKyM/x6ohf8C1Zr/AMmL/wHGjv+49OL///////////9+3ML/f9zD/4Dcwv9+28L/e9rA/3bZ
+        vv9w1rr/Z9S4/17Rs/9Qz63/Qcyn/3LewP////////////n///8MpH7/JbKP/zXQqUAAAAAAAAAAAP//
+        /wAAAAAAAAAAABymhN8dnn//BNGa/wDKjP8AxY3/sfHf/////////////////2nXt/9w1rv/c9e8/3TX
+        vP9x17z/a9W5/2TTtf9Y0K//SMyp/zXFoP9i07X/////////////////f/LR/wDQlf8epYT/Mb2a3wAA
+        AAAAAAAA////AAAAAAADlnJgFZR1/wq4iv8AzpH/AMCD/4rmzf//////////////////////WdGv/2PU
+        tf9p1rf/atS4/2nUtv9i0rT/Vc+u/0fKpv8zxZz/Ws+w//////////////////////8GyJL/ANCS/xLB
+        kv8tq4z/OMajYAAAAAD///8AAAAAAACHZt8NkW//ANKV/wDChP9i27r//////////////////////9Dx
+        6P9MzKn/Vc+v/17Rsv9g0rP/XNCx/1XNrv9Fyaf/McSd/1fPr///////////////////////QM2m/ynK
+        oP8JzJX/C9yh/ymmhf80spPfAAAAAP///wAAcUwwAHtc/wCrfP8AyIv/AMKK////////////////////
+        /////////////5Dgyv9Gyqb/TMyq/07Nq/9MzKn/Qcmj/y/Fnf9Wzq3//////////////////////57k
+        0v8av5T/Lceg/yzOo/8M05v/Hr6T/zCghf80spIw////AABoRYAAclT/AL2H/wDBhf9R1rL/////////
+        ////////4vfw//////////////////H8+P9KzKn/Ocah/zTFnv8qwpj/Us2t////////////////////
+        ////////DLqM/yDBlv8wxp//OM6m/xPPm/8Xz53/LZF5/y+fg4////8AAGNAvwB7Wf8Aw4j/ALyC/4bj
+        yP+g5tL/g93E/2HSsv9Pzqz/Us6s//////////////////////9Yzq//Gr2S/0jLp///////////////
+        /////////////yrDm/8SvI//JMGY/zDHn/81zKT/Is2e/xTUnf8nl3v/LJJ5v////wAAXz3vAIlg/wDA
+        hf8AuoD/quzZ/5Hjyv9628D/ada2/1jRsP9Jy6f/a9a4//////////////////////+Y4s7/////////
+        //////////////////+c4tD/AbaH/xW8kf8jwZj/LcWd/y/Jn/8kzJ3/E9Ca/yGjgf8ri3Tv////AABd
+        PP8Ak2b/AL6D/w/Ekv+m6tf/j+HJ/3vawP9p1rf/W9Gx/0rNqf85yJ//Nsaf////////////////////
+        /////////////////////////////wCwe/8AtoT/ELqP/xu+k/8jwZj/KMeb/yHKm/8QzZf/HqyG/ymI
+        cf////8AAF07/wCSZP8AvYL/GMWU/6Dn1P+K38f/ddi+/27Wuf+E3MX/leHN/6fm1f+l5tX/neLQ////
+        ////////////////////////////////////////j9/J/27Vuv9Tzq7/JsKY/xa/kv8aw5T/FcaW/wvL
+        lf8aqoT/J4dw/////wAAXTv/AJFk/wC9gP8GwY3/mObQ/5rkz/+26dv/y/Hl/8Dt3/+06tz/pebV/5bg
+        zP+g5NL//////////////v///f7+//7+/v//////7fn2////////////tOnb/6Ll0v+v6Nj/jeDI/zXK
+        o/8IxJD/BMqS/xaqgv8lh2//////AABeO+8AgVf/AL1//wDBif/R9uv/1PPq/8Tv5P+36t3/rujY/6Lk
+        0v+U4cv/jt7J//j8+///////+/38//f8+//2+/r/+Pz7//3+/v/m9/P/9Pv6//D6+P9/28L/jd7J/5jj
+        z/+h5dL/qOvX/4Hmyf8f1J//E596/yOJcO////8AAGA8vwB3U/8p06P/hufM/8Ty5f/D7+T/s+vb/6bm
+        1P+c4c//j9/K/4vcyP/t+fb///7///j8/P/0+/r/8vr5//P7+f/1+/r/+/39///////i9fL/ZNO1/3HW
+        vP992sH/htzG/4vhyv+S5dD/mO7W/6X74v80noT/Io90v////wAAZkCAAHla/33ny/945cb/nunV/7Xr
+        3v+l5tT/luDN/4ndxv992cL/1vLq//v9/P/1+/n/8vv4//L69//z+/j/9Pv5/7Xo2//x+vn/////////
+        //+y59n/aNS3/3LWvP932r//fNzD/4Ljyf+J7ND/l/bd/yORdf8knH6A////AABuRzAAdlT/Xc6x/23o
+        xv9s4MH/qurZ/5jiz/+I3cb/edjA/8ju5f/3/Pv/8vv4//H6+P/y+/j/6/f0/7np3v/7/fz//v7+/6fk
+        1f+56tz///////////9h0bT/aNW4/23Wu/9v3L//dOLG/37w0f9m1rn/Hpt8/ymujTD///8AAAAAAACD
+        X98po4X/Z+7K/1vgvP+A4sf/jOHK/3rZwv+r59f/9Pv6/+/69//v+vf/8vr4/9fy6/9n0rf/VM6t/6Di
+        0v/N7+f/adO4/1PMrf9t1Lr/i9zI/1/Rs/9h0rX/ZNe4/2bbvf9s5sb/ePfV/z2ylf8lrozfAAAAAP//
+        /wAAAAAAAJNsYAWQbf9U1rP/Vee//0rYsf993sb/pebV//P7+v/s+Pb/6/f1/+749v+s5tj/Vc2u/1jP
+        r/9ZzrD/btW5/1bOr/9Wza//Vs6v/1fOr/9Z0LD/WdCy/1vTtP9d1rX/Xt+8/2btyP9k4L//IaaF/y7D
+        nmAAAAAA////AAAAAAAAAAAAD6J9zyCjgv9S68L/P9+0/2Pevv/5////7/v6/+v59//j9/L/gtvF/1PN
+        r/9Wz7D/Wc+x/1nQsf9Zz7H/WM6w/1fPsP9UzrD/VM+w/1TPrv9U0a//U9Oy/1Tatv9Z5sD/Y/LL/zSx
+        lP8qupbPAAAAAAAAAAD///8AAAAAAAAAAAAYto4wGaeE/y23lP8+5rn/6/////j////w//3/ve/i/2bV
+        uP9Tzq7/Vc+v/1jPsP9Z0LL/WM+w/1fOsf9Wz7D/Us2w/1HOrf9Qzq3/T9Cu/0zSr/9M2LP/TeC5/1bt
+        xP9HxaX/KLKQ/zTPqDAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAkvpdgG6iF/y++m//e/////P///3rl
+        yf9G0K3/VdKy/1bPsf9Wz7H/Vs6w/1bPsP9Sza//Ucyu/0/Nrf9NzKz/S82s/0fOrP9G0a7/QdWv/0Le
+        tP9I6L7/Q8Ok/yitjP8yyKJgAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAmwJlgG6iF/yK3
+        kP8k3q7/H9el/x7Pn/8tzKT/Q9Cs/1HQsP9Q0K7/TM6u/0nMrf9Hzaz/RMyp/0LNqf8+zqn/ONGo/zTV
+        qf833rD/O+S4/zvCof8orIv/MMSfYAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAA
+        AAAkvpdgG6iE/xukgv8gy53/HNql/xzRn/8czJz/HcmZ/yXJnP8qyp7/Lcqg/yzLn/8nypz/JMqc/yTO
+        n/8l1KT/KN2r/y3Tpv8nq4n/JaqJ/yzAm2AAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAA
+        AAAAAAAAAAAAAAAAAAAato8wFKN/zxCScv8RnHn/DbqM/wjIlP8GyZT/BsaS/wbFkf8GxZH/B8WR/wfH
+        k/8IypX/DMmV/xG3jP8WoX3/Fph2/xqkgs8ft5EwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA////AAAA
+        AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJVvYACGZM8Aelr/AHlZ/wCFX/8AiWL/AJlr/wCb
+        bP8AlGf/AI5k/wB/W/8AeFj/AHtb/wCHZd8ClXBgAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
+        AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAABwSzAAaESAAGI/vwBf
+        Pd8AXTz/AF08/wBdPP8AXz3fAGJAvwBoRIAAcUswAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
+        AAAAAAAAAAAAAP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
+        /wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
+        /wD///8A////AP///wD///8A/+AD//+AAP/+AAA//AAAH/gAAA/wAAAH4AAAA+AAAAPAAAABwAAAAYAA
+        AACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAwAAAAcAAAAHgAAAD4AAAA/AA
+        AAf4AAAP/AAAH/4AAD//gAD//+AD//////8=
+</value>
+  </data>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs
index e25765c0d1ae9bccd455a13e0566e02ac17d971c..8971889c8b46a70669800e3c399041ce9925246b 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs
@@ -684,7 +684,7 @@ namespace ArdupilotMega.GCSViews
 
         private void BUT_setup_Click(object sender, EventArgs e)
         {
-            Form temp = new Setup.Setup();
+            Form temp = new GCSViews.ConfigurationView.Setup();
             ThemeManager.ApplyThemeTo(temp);
             temp.ShowDialog();
         }
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
index 651bfd7e74dd098e575fbbb2d300dfdd9fbbada8..fb77827749a74b2718aff9f109390d9633d1b19f 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs
@@ -219,6 +219,7 @@ namespace ArdupilotMega.GCSViews
 
         private void FlightData_Load(object sender, EventArgs e)
         {
+            MainV2.bs = bindingSource1;
 
             System.Threading.Thread t11 = new System.Threading.Thread(new System.Threading.ThreadStart(mainloop))
             {
@@ -275,14 +276,14 @@ namespace ArdupilotMega.GCSViews
                     {
                         //System.Threading.Thread.Sleep(1000);
 
-                        //comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RAW_CONTROLLER, 0); // request servoout
-                        comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTENDED_STATUS, MainV2.cs.ratestatus); // mode
-                        comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_POSITION, MainV2.cs.rateposition); // request gps
-                        comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTRA1, MainV2.cs.rateattitude); // request attitude
-                        comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTRA2, MainV2.cs.rateattitude); // request vfr
-                        comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTRA3, MainV2.cs.ratesensors); // request extra stuff - tridge
-                        comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RAW_SENSORS, MainV2.cs.ratesensors); // request raw sensor
-                        comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RC_CHANNELS, MainV2.cs.raterc); // request rc info
+                        //comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RAW_CONTROLLER, 0); // request servoout
+                        comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTENDED_STATUS, MainV2.cs.ratestatus); // mode
+                        comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.POSITION, MainV2.cs.rateposition); // request gps
+                        comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA1, MainV2.cs.rateattitude); // request attitude
+                        comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA2, MainV2.cs.rateattitude); // request vfr
+                        comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA3, MainV2.cs.ratesensors); // request extra stuff - tridge
+                        comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.cs.ratesensors); // request raw sensor
+                        comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RC_CHANNELS, MainV2.cs.raterc); // request rc info
                     }
                     catch { }
                     lastdata = DateTime.Now.AddSeconds(12); // prevent flooding
@@ -926,7 +927,7 @@ namespace ArdupilotMega.GCSViews
             {
                 MainV2.giveComport = true;
 
-                MainV2.comPort.setWP(gotohere, 0, MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT, (byte)2);
+                MainV2.comPort.setWP(gotohere, 0, MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT, (byte)2);
 
                 GuidedModeWP = new PointLatLngAlt(gotohere.lat, gotohere.lng, gotohere.alt,"Guided Mode");
 
@@ -1670,7 +1671,7 @@ namespace ArdupilotMega.GCSViews
                 return;
             }
 
-            MainV2.comPort.setMountConfigure(MAVLink.MAV_MOUNT_MODE.MAV_MOUNT_MODE_GPS_POINT, true, true, true);
+            MainV2.comPort.setMountConfigure(MAVLink.MAV_MOUNT_MODE.GPS_POINT, true, true, true);
             MainV2.comPort.setMountControl(gotolocation.Lat, gotolocation.Lng, (int)(intalt / MainV2.cs.multiplierdist), true);
 
         }
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx
index 2157889864e167f977576dcc9f4c32eb955ca38b..fcbfad4a2a0e8829f5b033c4add4272cbb3991a9 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx
@@ -910,16 +910,16 @@
     <value>NoControl</value>
   </data>
   <data name="BUT_log2kml.Location" type="System.Drawing.Point, System.Drawing">
-    <value>51, 32</value>
+    <value>29, 32</value>
   </data>
   <data name="BUT_log2kml.Size" type="System.Drawing.Size, System.Drawing">
-    <value>80, 23</value>
+    <value>127, 23</value>
   </data>
   <data name="BUT_log2kml.TabIndex" type="System.Int32, mscorlib">
     <value>76</value>
   </data>
   <data name="BUT_log2kml.Text" xml:space="preserve">
-    <value>Log &gt; KML</value>
+    <value>Tlog &gt; Kml or Graph</value>
   </data>
   <data name="&gt;&gt;BUT_log2kml.Name" xml:space="preserve">
     <value>BUT_log2kml</value>
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
index 490d6f88fa0dfaf906e9bb9b8ef82a0a8d118267..4c861632ad84cbe90f550301173f7e31157052c1 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
@@ -1164,7 +1164,7 @@ namespace ArdupilotMega.GCSViews
 
                         sw.Write((a + 1)); // seq
                         sw.Write("\t" + 0); // current
-                        sw.Write("\t" + (CHK_altmode.Checked == true ? (byte)MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL : (byte)MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT)); //frame 
+                        sw.Write("\t" + (CHK_altmode.Checked == true ? (byte)MAVLink.MAV_FRAME.GLOBAL : (byte)MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT)); //frame 
                         sw.Write("\t" + mode);
                         sw.Write("\t" + double.Parse(Commands.Rows[a].Cells[Param1.Index].Value.ToString()).ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
                         sw.Write("\t" + double.Parse(Commands.Rows[a].Cells[Param2.Index].Value.ToString()).ToString("0.000000", new System.Globalization.CultureInfo("en-US")));
@@ -1352,9 +1352,9 @@ namespace ArdupilotMega.GCSViews
 
                 ((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(0, "Set Home");
 
-                port.setWP(home, (ushort)0, MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL, 0);
+                port.setWP(home, (ushort)0, MAVLink.MAV_FRAME.GLOBAL, 0);
 
-                MAVLink.MAV_FRAME frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT;
+                MAVLink.MAV_FRAME frame = MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT;
 
                 // process grid to memory eeprom
                 for (int a = 0; a < Commands.Rows.Count - 0; a++)
@@ -1368,11 +1368,11 @@ namespace ArdupilotMega.GCSViews
                     {
                         if (CHK_altmode.Checked)
                         {
-                            frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL;
+                            frame = MAVLink.MAV_FRAME.GLOBAL;
                         }
                         else
                         {
-                            frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT;
+                            frame = MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT;
                         }
                     }
 
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs
index f28305e452d877a96d791674077c94f233422fb9..f5872fe2a3fc6e1a6bfc80b9ff6ae528d4e75b99 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs
@@ -49,6 +49,14 @@ namespace ArdupilotMega.GCSViews
         int simPort = 49000;
         int recvPort = 49005;
 
+        // gps buffer
+        int gpsbufferindex = 0;
+#if !MAVLINK10
+        ArdupilotMega.MAVLink.mavlink_gps_raw_t[] gpsbuffer = new MAVLink.mavlink_gps_raw_t[5];
+#else
+        ArdupilotMega.MAVLink.mavlink_gps_raw_int_t[] gpsbuffer = new MAVLink.mavlink_gps_raw_int_t[5];
+#endif
+
         // set defaults
         int rollgain = 10000;
         int pitchgain = 10000;
@@ -370,7 +378,6 @@ namespace ArdupilotMega.GCSViews
         /// <param name="write">true/false</param>
         private void xmlconfig(bool write)
         {
-            int fixme; // add profiles?
             if (write)
             {
                 ArdupilotMega.MainV2.config["REV_roll"] = CHKREV_roll.Checked.ToString();
@@ -572,11 +579,11 @@ namespace ArdupilotMega.GCSViews
                     {
                         if (CHK_quad.Checked && !RAD_aerosimrc.Checked)// || chkSensor.Checked && RAD_JSBSim.Checked)
                         {
-                            comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RAW_CONTROLLER, 0); // request servoout
+                            comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RAW_CONTROLLER, 0); // request servoout
                         }
                         else
                         {
-                            comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RAW_CONTROLLER, 50); // request servoout
+                            comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RAW_CONTROLLER, 50); // request servoout
                         }
                     }
                     catch { }
@@ -700,10 +707,10 @@ namespace ArdupilotMega.GCSViews
         float oldax = 0, olday = 0, oldaz = 0;
         DateTime oldtime = DateTime.Now;
 #if MAVLINK10
-        ArdupilotMega.MAVLink.__mavlink_gps_raw_int_t oldgps = new MAVLink.__mavlink_gps_raw_int_t();
+        ArdupilotMega.MAVLink.mavlink_gps_raw_int_t oldgps = new MAVLink.mavlink_gps_raw_int_t();
 #endif
 
-        ArdupilotMega.MAVLink.__mavlink_attitude_t oldatt = new ArdupilotMega.MAVLink.__mavlink_attitude_t();
+        ArdupilotMega.MAVLink.mavlink_attitude_t oldatt = new ArdupilotMega.MAVLink.mavlink_attitude_t();
 
         /// <summary>
         /// Recevied UDP packet, process and send required data to serial port.
@@ -714,18 +721,18 @@ namespace ArdupilotMega.GCSViews
         private void RECVprocess(byte[] data, int receviedbytes, ArdupilotMega.MAVLink comPort)
         {
 #if MAVLINK10
-            ArdupilotMega.MAVLink.__mavlink_hil_state_t hilstate = new ArdupilotMega.MAVLink.__mavlink_hil_state_t();
+            ArdupilotMega.MAVLink.mavlink_hil_state_t hilstate = new ArdupilotMega.MAVLink.mavlink_hil_state_t();
 
-            ArdupilotMega.MAVLink.__mavlink_gps_raw_int_t gps = new ArdupilotMega.MAVLink.__mavlink_gps_raw_int_t();
+            ArdupilotMega.MAVLink.mavlink_gps_raw_int_t gps = new ArdupilotMega.MAVLink.mavlink_gps_raw_int_t();
 #else
-            ArdupilotMega.MAVLink.__mavlink_gps_raw_t gps = new ArdupilotMega.MAVLink.__mavlink_gps_raw_t();
+            ArdupilotMega.MAVLink.mavlink_gps_raw_t gps = new ArdupilotMega.MAVLink.mavlink_gps_raw_t();
 #endif
-            ArdupilotMega.MAVLink.__mavlink_raw_imu_t imu = new ArdupilotMega.MAVLink.__mavlink_raw_imu_t();
+            ArdupilotMega.MAVLink.mavlink_raw_imu_t imu = new ArdupilotMega.MAVLink.mavlink_raw_imu_t();
 
 
-            ArdupilotMega.MAVLink.__mavlink_attitude_t att = new ArdupilotMega.MAVLink.__mavlink_attitude_t();
+            ArdupilotMega.MAVLink.mavlink_attitude_t att = new ArdupilotMega.MAVLink.mavlink_attitude_t();
 
-            ArdupilotMega.MAVLink.__mavlink_vfr_hud_t asp = new ArdupilotMega.MAVLink.__mavlink_vfr_hud_t();
+            ArdupilotMega.MAVLink.mavlink_vfr_hud_t asp = new ArdupilotMega.MAVLink.mavlink_vfr_hud_t();
 
             if (data[0] == 'D' && data[1] == 'A')
             {
@@ -830,11 +837,11 @@ namespace ArdupilotMega.GCSViews
                 gps.fix_type = 3;
                                 if (xplane9)
                 {
-                    gps.cog = ((float)DATA[19][2]);
+                    gps.cog = (ushort)((float)DATA[19][2]);
                 }
                 else
                 {
-                    gps.cog = ((float)DATA[18][2]);
+                    gps.cog = (ushort)((float)DATA[18][2]);
                 }
                 gps.lat = (int)(DATA[20][0] * 1.0e7);
                 gps.lon = (int)(DATA[20][1] * 1.0e7);
@@ -1163,7 +1170,11 @@ namespace ArdupilotMega.GCSViews
                 sitlout.alt = gps.alt;
                 sitlout.lat = gps.lat;
                 sitlout.lon = gps.lon;
+#if !MAVLINK10
                 sitlout.heading = gps.hdg;
+#else
+                sitlout.heading = gps.cog;
+#endif
 
                 sitlout.v_north =  DATA[21][4];
                 sitlout.v_east = DATA[21][5];
@@ -1241,7 +1252,7 @@ namespace ArdupilotMega.GCSViews
 
 #endif
 
-                MAVLink.__mavlink_raw_pressure_t pres = new MAVLink.__mavlink_raw_pressure_t();
+                MAVLink.mavlink_raw_pressure_t pres = new MAVLink.mavlink_raw_pressure_t();
                 double calc = (101325 * Math.Pow(1 - 2.25577 * Math.Pow(10, -5) * gps.alt, 5.25588)); // updated from valid gps
                 pres.press_diff1 = (short)(int)(calc - 101325); // 0 alt is 0 pa
 
@@ -1256,7 +1267,15 @@ namespace ArdupilotMega.GCSViews
             {
                 lastgpsupdate = DateTime.Now;
 
-                comPort.sendPacket(gps);
+                // save current fix = 3
+                gpsbuffer[gpsbufferindex % gpsbuffer.Length] = gps;
+
+//                Console.WriteLine((gpsbufferindex % gpsbuffer.Length) + " " + ((gpsbufferindex + (gpsbuffer.Length - 1)) % gpsbuffer.Length));
+
+                // return buffer index + 5 = (3 + 5) = 8 % 6 = 2
+                comPort.sendPacket(gpsbuffer[(gpsbufferindex + (gpsbuffer.Length - 1)) % gpsbuffer.Length]);
+
+                gpsbufferindex++;
             }
 #endif
         }
diff --git a/Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs b/Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs
index 16414cbbb5849d8061e7c941470cbac88792568c..98d32185e9bde12e09dfcf0ff0c326bb603d3c0f 100644
--- a/Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs
+++ b/Tools/ArdupilotMegaPlanner/HIL/QuadCopter.cs
@@ -330,14 +330,14 @@ namespace ArdupilotMega.HIL
 
             // send to apm
 #if MAVLINK10
-            ArdupilotMega.MAVLink.__mavlink_gps_raw_int_t gps = new ArdupilotMega.MAVLink.__mavlink_gps_raw_int_t();
+            ArdupilotMega.MAVLink.mavlink_gps_raw_int_t gps = new ArdupilotMega.MAVLink.mavlink_gps_raw_int_t();
 #else
-            ArdupilotMega.MAVLink.__mavlink_gps_raw_t gps = new ArdupilotMega.MAVLink.__mavlink_gps_raw_t();
+            ArdupilotMega.MAVLink.mavlink_gps_raw_t gps = new ArdupilotMega.MAVLink.mavlink_gps_raw_t();
 #endif
 
-            ArdupilotMega.MAVLink.__mavlink_attitude_t att = new ArdupilotMega.MAVLink.__mavlink_attitude_t();
+            ArdupilotMega.MAVLink.mavlink_attitude_t att = new ArdupilotMega.MAVLink.mavlink_attitude_t();
 
-            ArdupilotMega.MAVLink.__mavlink_vfr_hud_t asp = new ArdupilotMega.MAVLink.__mavlink_vfr_hud_t();
+            ArdupilotMega.MAVLink.mavlink_vfr_hud_t asp = new ArdupilotMega.MAVLink.mavlink_vfr_hud_t();
 
             att.roll = (float)roll * deg2rad;
             att.pitch = (float)pitch * deg2rad;
@@ -380,7 +380,7 @@ namespace ArdupilotMega.HIL
 
             MainV2.comPort.sendPacket(att);
 
-            MAVLink.__mavlink_raw_pressure_t pres = new MAVLink.__mavlink_raw_pressure_t();
+            MAVLink.mavlink_raw_pressure_t pres = new MAVLink.mavlink_raw_pressure_t();
             double calc = (101325 * Math.Pow(1 - 2.25577 * Math.Pow(10, -5) * gps.alt, 5.25588));
             pres.press_diff1 = (short)(int)(calc); // 0 alt is 0 pa
 
diff --git a/Tools/ArdupilotMegaPlanner/HUD.cs b/Tools/ArdupilotMegaPlanner/HUD.cs
index 4c3795a88684bf252a43dff8f5f098cd932f20fa..e87062fb4657561d65fb584f4ea526a9090b1c72 100644
--- a/Tools/ArdupilotMegaPlanner/HUD.cs
+++ b/Tools/ArdupilotMegaPlanner/HUD.cs
@@ -258,7 +258,6 @@ namespace hud
             {
                 e.Graphics.Clear(this.BackColor);
                 e.Graphics.Flush();
-                //return;
             }
 
             if ((DateTime.Now - starttime).TotalMilliseconds < 30 && (_bgimage == null))
diff --git a/Tools/ArdupilotMegaPlanner/JoystickSetup.cs b/Tools/ArdupilotMegaPlanner/JoystickSetup.cs
index 9d491c7a68138d9301c95425f28b19646cc14aa4..92e7c613d49f4a727bbd24f67c813dd715965415 100644
--- a/Tools/ArdupilotMegaPlanner/JoystickSetup.cs
+++ b/Tools/ArdupilotMegaPlanner/JoystickSetup.cs
@@ -148,7 +148,7 @@ namespace ArdupilotMega
             }
             else
             {
-                MAVLink.__mavlink_rc_channels_override_t rc = new MAVLink.__mavlink_rc_channels_override_t();
+                MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t();
 
                 rc.target_component = MainV2.comPort.compid;
                 rc.target_system = MainV2.comPort.sysid;
diff --git a/Tools/ArdupilotMegaPlanner/MAVLink.cs b/Tools/ArdupilotMegaPlanner/MAVLink.cs
index 8299c9e585f054c86495ab3dae968b443e00fb6f..f608a218e53e6af883e56e5b158069769863f316 100644
--- a/Tools/ArdupilotMegaPlanner/MAVLink.cs
+++ b/Tools/ArdupilotMegaPlanner/MAVLink.cs
@@ -269,7 +269,7 @@ namespace ArdupilotMega
 
                     if (buffer.Length > 5 && buffer1.Length > 5 && buffer[3] == buffer1[3] && buffer[4] == buffer1[4])
                     {
-                        __mavlink_heartbeat_t hb = buffer.ByteArrayToStructure<__mavlink_heartbeat_t>(6);
+                        mavlink_heartbeat_t hb = buffer.ByteArrayToStructure<mavlink_heartbeat_t>(6);
 
                         mavlinkversion = hb.mavlink_version;
                         aptype = hb.type;
@@ -345,7 +345,7 @@ namespace ArdupilotMega
         {
             bool validPacket = false;
             byte a = 0;
-            foreach (Type ty in mavstructs)
+            foreach (Type ty in MAVLINK_MESSAGE_INFO)
             {
                 if (ty == indata.GetType())
                 {
@@ -432,7 +432,7 @@ namespace ArdupilotMega
 
             try
             {
-                if (logfile != null)
+                if (logfile != null && logfile.BaseStream.CanWrite)
                 {
                     lock (logwritelock)
                     {
@@ -491,7 +491,7 @@ namespace ArdupilotMega
 
             MainV2.giveComport = true;
 
-            __mavlink_param_set_t req = new __mavlink_param_set_t();
+            mavlink_param_set_t req = new mavlink_param_set_t();
             req.target_system = sysid;
             req.target_component = compid;
 
@@ -534,7 +534,7 @@ namespace ArdupilotMega
                 {
                     if (buffer[5] == MAVLINK_MSG_ID_PARAM_VALUE)
                     {
-                        __mavlink_param_value_t par = buffer.ByteArrayToStructure<__mavlink_param_value_t>(6);
+                        mavlink_param_value_t par = buffer.ByteArrayToStructure<mavlink_param_value_t>(6);
 
                         string st = System.Text.ASCIIEncoding.ASCII.GetString(par.param_id);
 
@@ -612,7 +612,7 @@ namespace ArdupilotMega
 
             goagain:
 
-            __mavlink_param_request_list_t req = new __mavlink_param_request_list_t();
+            mavlink_param_request_list_t req = new mavlink_param_request_list_t();
             req.target_system = sysid;
             req.target_component = compid;
 
@@ -657,7 +657,7 @@ namespace ArdupilotMega
                         restart = DateTime.Now;
                         start = DateTime.Now;
 
-                        __mavlink_param_value_t par = buffer.ByteArrayToStructure<__mavlink_param_value_t>(6);
+                        mavlink_param_value_t par = buffer.ByteArrayToStructure<mavlink_param_value_t>(6);
 
                         // set new target
                         param_total = (par.param_count - 1);
@@ -755,7 +755,7 @@ namespace ArdupilotMega
         /// </summary>
         public void stopall(bool forget)
         {
-            __mavlink_request_data_stream_t req = new __mavlink_request_data_stream_t();
+            mavlink_request_data_stream_t req = new mavlink_request_data_stream_t();
             req.target_system = sysid;
             req.target_component = compid;
 
@@ -780,14 +780,14 @@ namespace ArdupilotMega
         public void setWPACK()
         {
 #if MAVLINK10
-            MAVLink.__mavlink_mission_ack_t req = new MAVLink.__mavlink_mission_ack_t();
+            MAVLink.mavlink_mission_ack_t req = new MAVLink.mavlink_mission_ack_t();
             req.target_system = sysid;
             req.target_component = compid;
             req.type = 0;
 
             generatePacket(MAVLINK_MSG_ID_MISSION_ACK, req);
 #else
-            MAVLink.__mavlink_waypoint_ack_t req = new MAVLink.__mavlink_waypoint_ack_t();
+            MAVLink.mavlink_waypoint_ack_t req = new MAVLink.mavlink_waypoint_ack_t();
             req.target_system = sysid;
             req.target_component = compid;
             req.type = 0;
@@ -799,10 +799,10 @@ namespace ArdupilotMega
         public bool setWPCurrent(ushort index)
         {
 #if MAVLINK10
-            MainV2.givecomport = true;
+            MainV2.giveComport = true;
             byte[] buffer;
 
-            __mavlink_mission_set_current_t req = new __mavlink_mission_set_current_t();
+            mavlink_mission_set_current_t req = new mavlink_mission_set_current_t();
 
             req.target_system = sysid;
             req.target_component = compid;
@@ -825,7 +825,7 @@ namespace ArdupilotMega
                         retrys--;
                         continue;
                     }
-                    MainV2.givecomport = false;
+                    MainV2.giveComport = false;
                     throw new Exception("Timeout on read - setWPCurrent");
                 }
 
@@ -834,7 +834,7 @@ namespace ArdupilotMega
                 {
                     if (buffer[5] == MAVLINK_MSG_ID_MISSION_CURRENT)
                     {
-                        MainV2.givecomport = false;
+                        MainV2.giveComport = false;
                         return true;
                     }
                 }
@@ -844,10 +844,10 @@ namespace ArdupilotMega
         public bool doCommand(MAV_CMD actionid, float p1, float p2, float p3, float p4, float p5, float p6, float p7)
         {
 
-            MainV2.givecomport = true;
+            MainV2.giveComport = true;
             byte[] buffer;
 
-            __mavlink_command_long_t req = new __mavlink_command_long_t();
+            mavlink_command_long_t req = new mavlink_command_long_t();
 
             req.target_system = sysid;
             req.target_component = compid;
@@ -888,7 +888,7 @@ namespace ArdupilotMega
                         retrys--;
                         continue;
                     }
-                    MainV2.givecomport = false;
+                    MainV2.giveComport = false;
                     throw new Exception("Timeout on read - doAction");
                 }
 
@@ -899,17 +899,17 @@ namespace ArdupilotMega
                     {
 
 
-                        var ack = buffer.ByteArrayToStructure<__mavlink_command_ack_t>(6);
+                        var ack = buffer.ByteArrayToStructure<mavlink_command_ack_t>(6);
 
 
-                        if (ack.result == (byte)MAV_RESULT.MAV_RESULT_ACCEPTED)
+                        if (ack.result == (byte)MAV_RESULT.ACCEPTED)
                         {
-                            MainV2.givecomport = false;
+                            MainV2.giveComport = false;
                             return true;
                         }
                         else
                         {
-                            MainV2.givecomport = false;
+                            MainV2.giveComport = false;
                             return false;
                         }
                     }
@@ -919,7 +919,7 @@ namespace ArdupilotMega
             MainV2.giveComport = true;
             byte[] buffer;
 
-            __mavlink_waypoint_set_current_t req = new __mavlink_waypoint_set_current_t();
+            mavlink_waypoint_set_current_t req = new mavlink_waypoint_set_current_t();
 
             req.target_system = sysid;
             req.target_component = compid;
@@ -963,7 +963,7 @@ namespace ArdupilotMega
             MainV2.giveComport = true;
             byte[] buffer;
 
-            __mavlink_action_t req = new __mavlink_action_t();
+            mavlink_action_t req = new mavlink_action_t();
 
             req.target = sysid;
             req.target_component = compid;
@@ -1032,10 +1032,10 @@ namespace ArdupilotMega
 
             switch (id)
             {
-                case (byte)MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_ALL:
+                case (byte)MAVLink.MAV_DATA_STREAM.ALL:
 
                     break;
-                case (byte)MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTENDED_STATUS:
+                case (byte)MAVLink.MAV_DATA_STREAM.EXTENDED_STATUS:
                     if (packetspersecondbuild[MAVLINK_MSG_ID_SYS_STATUS] < DateTime.Now.AddSeconds(-2))
                         break;
                     pps = packetspersecond[MAVLINK_MSG_ID_SYS_STATUS];
@@ -1044,7 +1044,7 @@ namespace ArdupilotMega
                         return;
                     }
                     break;
-                case (byte)MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTRA1:
+                case (byte)MAVLink.MAV_DATA_STREAM.EXTRA1:
                     if (packetspersecondbuild[MAVLINK_MSG_ID_ATTITUDE] < DateTime.Now.AddSeconds(-2))
                         break;
                     pps = packetspersecond[MAVLINK_MSG_ID_ATTITUDE];
@@ -1053,7 +1053,7 @@ namespace ArdupilotMega
                         return;
                     }
                     break;
-                case (byte)MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTRA2:
+                case (byte)MAVLink.MAV_DATA_STREAM.EXTRA2:
                     if (packetspersecondbuild[MAVLINK_MSG_ID_VFR_HUD] < DateTime.Now.AddSeconds(-2))
                         break;
                     pps = packetspersecond[MAVLINK_MSG_ID_VFR_HUD];
@@ -1062,16 +1062,16 @@ namespace ArdupilotMega
                         return;
                     }
                     break;
-                case (byte)MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTRA3:
-                    if (packetspersecondbuild[MAVLINK_MSG_ID_DCM] < DateTime.Now.AddSeconds(-2))
+                case (byte)MAVLink.MAV_DATA_STREAM.EXTRA3:
+                    if (packetspersecondbuild[MAVLINK_MSG_ID_AHRS] < DateTime.Now.AddSeconds(-2))
                         break;
-                    pps = packetspersecond[MAVLINK_MSG_ID_DCM];
+                    pps = packetspersecond[MAVLINK_MSG_ID_AHRS];
                     if (hzratecheck(pps, hzrate))
                     {
                         return;
                     }
                     break;
-                case (byte)MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_POSITION:
+                case (byte)MAVLink.MAV_DATA_STREAM.POSITION:
                     // ac2 does not send rate position
                     if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
                         return;
@@ -1083,7 +1083,7 @@ namespace ArdupilotMega
                         return;
                     }
                     break;
-                case (byte)MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RAW_CONTROLLER:
+                case (byte)MAVLink.MAV_DATA_STREAM.RAW_CONTROLLER:
                     if (packetspersecondbuild[MAVLINK_MSG_ID_RC_CHANNELS_SCALED] < DateTime.Now.AddSeconds(-2))
                         break;
                     pps = packetspersecond[MAVLINK_MSG_ID_RC_CHANNELS_SCALED];
@@ -1092,7 +1092,7 @@ namespace ArdupilotMega
                         return;
                     }
                     break;
-                case (byte)MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RAW_SENSORS:
+                case (byte)MAVLink.MAV_DATA_STREAM.RAW_SENSORS:
                     if (packetspersecondbuild[MAVLINK_MSG_ID_RAW_IMU] < DateTime.Now.AddSeconds(-2))
                         break;
                     pps = packetspersecond[MAVLINK_MSG_ID_RAW_IMU];
@@ -1101,7 +1101,7 @@ namespace ArdupilotMega
                         return;
                     }
                     break;
-                case (byte)MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RC_CHANNELS:
+                case (byte)MAVLink.MAV_DATA_STREAM.RC_CHANNELS:
                     if (packetspersecondbuild[MAVLINK_MSG_ID_RC_CHANNELS_RAW] < DateTime.Now.AddSeconds(-2))
                         break;
                     pps = packetspersecond[MAVLINK_MSG_ID_RC_CHANNELS_RAW];
@@ -1154,7 +1154,7 @@ namespace ArdupilotMega
 
         void getDatastream(byte id, byte hzrate)
         {
-            __mavlink_request_data_stream_t req = new __mavlink_request_data_stream_t();
+            mavlink_request_data_stream_t req = new mavlink_request_data_stream_t();
             req.target_system = sysid;
             req.target_component = compid;
 
@@ -1176,7 +1176,7 @@ namespace ArdupilotMega
             MainV2.giveComport = true;
             byte[] buffer;
 #if MAVLINK10
-            __mavlink_mission_request_list_t req = new __mavlink_mission_request_list_t();
+            mavlink_mission_request_list_t req = new mavlink_mission_request_list_t();
 
             req.target_system = sysid;
             req.target_component = compid;
@@ -1193,13 +1193,13 @@ namespace ArdupilotMega
                 {
                     if (retrys > 0)
                     {
-                        log.Info("getWPCount Retry " + retrys + " - giv com " + MainV2.givecomport);
+                        log.Info("getWPCount Retry " + retrys + " - giv com " + MainV2.giveComport);
                         generatePacket(MAVLINK_MSG_ID_MISSION_REQUEST_LIST, req);
                         start = DateTime.Now;
                         retrys--;
                         continue;
                     }
-                    MainV2.givecomport = false;
+                    MainV2.giveComport = false;
                     //return (byte)int.Parse(param["WP_TOTAL"].ToString());
                     throw new Exception("Timeout on read - getWPCount");
                 }
@@ -1212,11 +1212,11 @@ namespace ArdupilotMega
 
 
 
-                        var count = buffer.ByteArrayToStructure<__mavlink_mission_count_t>(6);
+                        var count = buffer.ByteArrayToStructure<mavlink_mission_count_t>(6);
 
 
                         log.Info("wpcount: " + count.count);
-                        MainV2.givecomport = false;
+                        MainV2.giveComport = false;
                         return (byte)count.count; // should be ushort, but apm has limited wp count < byte
                     }
                     else
@@ -1227,7 +1227,7 @@ namespace ArdupilotMega
             }
 #else
 
-            __mavlink_waypoint_request_list_t req = new __mavlink_waypoint_request_list_t();
+            mavlink_waypoint_request_list_t req = new mavlink_waypoint_request_list_t();
 
             req.target_system = sysid;
             req.target_component = compid;
@@ -1284,7 +1284,7 @@ namespace ArdupilotMega
             MainV2.giveComport = true;
             Locationwp loc = new Locationwp();
 #if MAVLINK10
-            __mavlink_mission_request_t req = new __mavlink_mission_request_t();
+            mavlink_mission_request_t req = new mavlink_mission_request_t();
 
             req.target_system = sysid;
             req.target_component = compid;
@@ -1311,7 +1311,7 @@ namespace ArdupilotMega
                         retrys--;
                         continue;
                     }
-                    MainV2.givecomport = false;
+                    MainV2.giveComport = false;
                     throw new Exception("Timeout on read - getWP");
                 }
                 //Console.WriteLine("getwp read " + DateTime.Now.Millisecond);
@@ -1326,12 +1326,12 @@ namespace ArdupilotMega
 
                         //Array.Copy(buffer, 6, buffer, 0, buffer.Length - 6);
 
-                        var wp = buffer.ByteArrayToStructure<__mavlink_mission_item_t>(6);
+                        var wp = buffer.ByteArrayToStructure<mavlink_mission_item_t>(6);
 
 
 #else
 
-            __mavlink_waypoint_request_t req = new __mavlink_waypoint_request_t();
+            mavlink_waypoint_request_t req = new mavlink_waypoint_request_t();
 
             req.target_system = sysid;
             req.target_component = compid;
@@ -1369,7 +1369,7 @@ namespace ArdupilotMega
                     if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT)
                     {
                         //Console.WriteLine("getwp ans " + DateTime.Now.Millisecond);
-                        __mavlink_waypoint_t wp = buffer.ByteArrayToStructure<__mavlink_waypoint_t>(6);
+                        mavlink_waypoint_t wp = buffer.ByteArrayToStructure<mavlink_waypoint_t>(6);
 
 #endif
 
@@ -1499,7 +1499,7 @@ namespace ArdupilotMega
 
                     textoutput = string.Format("{0:X} {1:X} {2:X} {3:X} {4:X} {5:X} ", header, length, seq, sysid, compid, messid);
 
-                    object data = Activator.CreateInstance(mavstructs[messid]);
+                    object data = Activator.CreateInstance(MAVLINK_MESSAGE_INFO[messid]);
 
                     MavlinkUtil.ByteArrayToStructure(datin, ref data, 6);
 
@@ -1561,8 +1561,8 @@ namespace ArdupilotMega
         public void setWPTotal(ushort wp_total)
         {
 #if MAVLINK10		
-            MainV2.givecomport = true;
-            __mavlink_mission_count_t req = new __mavlink_mission_count_t();
+            MainV2.giveComport = true;
+            mavlink_mission_count_t req = new mavlink_mission_count_t();
 
             req.target_system = sysid;
             req.target_component = compid; // MAVLINK_MSG_ID_MISSION_COUNT
@@ -1586,7 +1586,7 @@ namespace ArdupilotMega
                         retrys--;
                         continue;
                     }
-                    MainV2.givecomport = false;
+                    MainV2.giveComport = false;
                     throw new Exception("Timeout on read - setWPTotal");
                 }
                 byte[] buffer = readPacket();
@@ -1597,7 +1597,7 @@ namespace ArdupilotMega
 
 
 
-                        var request = buffer.ByteArrayToStructure<__mavlink_mission_request_t>(6);
+                        var request = buffer.ByteArrayToStructure<mavlink_mission_request_t>(6);
 
                         if (request.seq == 0)
                         {
@@ -1605,7 +1605,7 @@ namespace ArdupilotMega
                                 param["WP_TOTAL"] = (float)wp_total - 1;
                             if (param["CMD_TOTAL"] != null)
                                 param["CMD_TOTAL"] = (float)wp_total - 1;
-                            MainV2.givecomport = false;
+                            MainV2.giveComport = false;
                             return;
                         }
                     }
@@ -1617,7 +1617,7 @@ namespace ArdupilotMega
             }
 #else
             MainV2.giveComport = true;
-            __mavlink_waypoint_count_t req = new __mavlink_waypoint_count_t();
+            mavlink_waypoint_count_t req = new mavlink_waypoint_count_t();
 
             req.target_system = sysid;
             req.target_component = compid; // MAVLINK_MSG_ID_WAYPOINT_COUNT
@@ -1649,7 +1649,7 @@ namespace ArdupilotMega
                 {
                     if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_REQUEST)
                     {
-                        __mavlink_waypoint_request_t request = buffer.ByteArrayToStructure<__mavlink_waypoint_request_t>(6);
+                        mavlink_waypoint_request_t request = buffer.ByteArrayToStructure<mavlink_waypoint_request_t>(6);
 
                         if (request.seq == 0)
                         {
@@ -1682,9 +1682,9 @@ namespace ArdupilotMega
         {
             MainV2.giveComport = true;
 #if MAVLINK10
-            __mavlink_mission_item_t req = new __mavlink_mission_item_t();
+            mavlink_mission_item_t req = new mavlink_mission_item_t();
 #else
-            __mavlink_waypoint_t req = new __mavlink_waypoint_t();
+            mavlink_waypoint_t req = new mavlink_waypoint_t();
 #endif
 
             req.target_system = sysid;
@@ -1797,7 +1797,7 @@ namespace ArdupilotMega
                     {
 
 
-                        var ans = buffer.ByteArrayToStructure<__mavlink_mission_ack_t>(6);
+                        var ans = buffer.ByteArrayToStructure<mavlink_mission_ack_t>(6);
 
 
                         log.Info("set wp " + index + " ACK 47 : " + buffer[5] + " ans " + Enum.Parse(typeof(MAV_MISSION_RESULT), ans.type.ToString()));
@@ -1805,7 +1805,7 @@ namespace ArdupilotMega
                     }
                     else if (buffer[5] == MAVLINK_MSG_ID_MISSION_REQUEST)
                     {
-                        var ans = buffer.ByteArrayToStructure<__mavlink_mission_request_t>(6);
+                        var ans = buffer.ByteArrayToStructure<mavlink_mission_request_t>(6);
 
 
 
@@ -1813,12 +1813,12 @@ namespace ArdupilotMega
                         if (ans.seq == (index + 1))
                         {
                             log.Info("set wp doing " + index + " req " + ans.seq + " REQ 40 : " + buffer[5]);
-                            MainV2.givecomport = false;
+                            MainV2.giveComport = false;
                             break;
                         }
                         else
                         {
-                            log.Info("set wp fail doing " + index + " req " + ans.seq + " ACK 47 or REQ 40 : " + buffer[5] + " seq {0} ts {1} tc {2}", req.seq, req.target_system, req.target_component);
+                            log.InfoFormat("set wp fail doing " + index + " req " + ans.seq + " ACK 47 or REQ 40 : " + buffer[5] + " seq {0} ts {1} tc {2}", req.seq, req.target_system, req.target_component);
                             //break;
                         }
                     }
@@ -1828,13 +1828,13 @@ namespace ArdupilotMega
                     }
 #else
                     if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_ACK)
-                    { //__mavlink_waypoint_request_t
+                    { //mavlink_waypoint_request_t
                         log.Info("set wp " + index + " ACK 47 : " + buffer[5]);
                         break;
                     }
                     else if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_REQUEST)
                     {
-                        __mavlink_waypoint_request_t ans = buffer.ByteArrayToStructure<__mavlink_waypoint_request_t>(6);
+                        mavlink_waypoint_request_t ans = buffer.ByteArrayToStructure<mavlink_waypoint_request_t>(6);
 
                         if (ans.seq == (index + 1))
                         {
@@ -1859,7 +1859,7 @@ namespace ArdupilotMega
 
         public void setMountConfigure(MAV_MOUNT_MODE mountmode, bool stabroll, bool stabpitch, bool stabyaw)
         {
-            __mavlink_mount_configure_t req = new __mavlink_mount_configure_t();
+            mavlink_mount_configure_t req = new mavlink_mount_configure_t();
 
             req.target_system = sysid;
             req.target_component = compid;
@@ -1875,7 +1875,7 @@ namespace ArdupilotMega
 
         public void setMountControl(double pa, double pb, double pc, bool islatlng)
         {
-            __mavlink_mount_control_t req = new __mavlink_mount_control_t();
+            mavlink_mount_control_t req = new mavlink_mount_control_t();
 
             req.target_system = sysid;
             req.target_component = compid;
@@ -1902,7 +1902,7 @@ namespace ArdupilotMega
 #if MAVLINK10
             try
             {
-                MAVLink.__mavlink_set_mode_t mode = new MAVLink.__mavlink_set_mode_t();
+                MAVLink.mavlink_set_mode_t mode = new MAVLink.mavlink_set_mode_t();
 
                 if (Common.translateMode(modein, ref mode))
                 {
@@ -1915,9 +1915,9 @@ namespace ArdupilotMega
 #else
             try
             {
-                MAVLink.__mavlink_set_nav_mode_t navmode = new MAVLink.__mavlink_set_nav_mode_t();
+                MAVLink.mavlink_set_nav_mode_t navmode = new MAVLink.mavlink_set_nav_mode_t();
 
-                MAVLink.__mavlink_set_mode_t mode = new MAVLink.__mavlink_set_mode_t();
+                MAVLink.mavlink_set_mode_t mode = new MAVLink.mavlink_set_mode_t();
 
                 if (Common.translateMode(modein, ref navmode, ref mode))
                 {
@@ -2026,13 +2026,14 @@ namespace ArdupilotMega
                             if (BaseStream.IsOpen)
                             {
                                 temp[count] = (byte)BaseStream.ReadByte();
-                                if (rawlogfile != null)
+                                if (rawlogfile != null && rawlogfile.BaseStream.CanWrite)
                                     rawlogfile.Write(temp[count]);
                             }
                         }
                     }
-                    catch (Exception e) { log.Info("MAVLink readpacket read error: " + e.Message); break; }
+                    catch (Exception e) { log.Info("MAVLink readpacket read error: " + e.ToString()); break; }
 
+                    // check if looks like a mavlink packet and check for exclusions and write to console
                     if (temp[0] != 254 && temp[0] != 'U' || lastbad[0] == 'I' && lastbad[1] == 'M' || lastbad[1] == 'G' || lastbad[1] == 'A') // out of sync "AUTO" "GUIDED" "IMU"
                     {
                         if (temp[0] >= 0x20 && temp[0] <= 127 || temp[0] == '\n' || temp[0] == '\r')
@@ -2049,6 +2050,7 @@ namespace ArdupilotMega
                     // reset count on valid packet
                     readcount = 0;
 
+
                     if (temp[0] == 'U' || temp[0] == 254)
                     {
                         length = temp[1] + 6 + 2 - 2; // data + header + checksum - U - length
@@ -2058,8 +2060,13 @@ namespace ArdupilotMega
                             {
                                 if (sysid != temp[3] || compid != temp[4])
                                 {
-                                    log.InfoFormat("Mavlink Bad Packet (not addressed to this MAV) got {0} {1} vs {2} {3}", temp[3], temp[4], sysid, compid);
-                                    return new byte[0];
+                                    if (temp[3] == '3' && temp[4] == 'D')
+                                    {
+                                        // this is a 3dr radio rssi packet
+                                    } else {
+                                        log.InfoFormat("Mavlink Bad Packet (not addressed to this MAV) got {0} {1} vs {2} {3}", temp[3], temp[4], sysid, compid);
+                                        return new byte[0];
+                                    }
                                 }
                             }
 
@@ -2085,9 +2092,10 @@ namespace ArdupilotMega
                                     if (BaseStream.IsOpen)
                                     {
                                         int read = BaseStream.Read(temp, 6, length - 4);
-                                        if (rawlogfile != null)
+                                        if (rawlogfile != null && rawlogfile.BaseStream.CanWrite)
                                         {
-                                            rawlogfile.Write(temp, 0, read);
+                                            // write only what we read, temp is the whole packet, so 6-end
+                                            rawlogfile.Write(temp, 6, read);
                                             rawlogfile.BaseStream.Flush();
                                         }
                                     }
@@ -2111,11 +2119,11 @@ namespace ArdupilotMega
             if (packetlosttimer.AddSeconds(10) < DateTime.Now)
             {
                 packetlosttimer = DateTime.Now;
-                packetslost = (int)(packetslost * 0.8f);
-                packetsnotlost = (int)(packetsnotlost * 0.8f);
+                packetslost = (packetslost * 0.8f);
+                packetsnotlost = (packetsnotlost * 0.8f);
             }
 
-            MainV2.cs.linkqualitygcs = (ushort)((packetsnotlost / (packetsnotlost + packetslost)) * 100);
+            MainV2.cs.linkqualitygcs = (ushort)((packetsnotlost / (packetsnotlost + packetslost)) * 100.0);
 
             if (bpstime.Second != DateTime.Now.Second && !logreadmode)
             {
@@ -2161,7 +2169,7 @@ namespace ArdupilotMega
 
             if (temp.Length < 5 || temp[temp.Length - 1] != (crc >> 8) || temp[temp.Length - 2] != (crc & 0xff))
             {
-                int packetno = 0;
+                int packetno = -1;
                 if (temp.Length > 5)
                 {
                     packetno = temp[5];
@@ -2172,28 +2180,35 @@ namespace ArdupilotMega
 
             try
             {
-
                 if ((temp[0] == 'U' || temp[0] == 254) && temp.Length >= temp[1])
                 {
-                    if (temp[2] != ((recvpacketcount + 1) % 0x100))
+                    if (temp[3] == '3' && temp[4] == 'D')
                     {
-                        synclost++; // actualy sync loss's
 
-                        if (temp[2] < ((recvpacketcount + 1) % 0x100))
-                        {
-                            packetslost += 0x100 - recvpacketcount + temp[2];
-                        }
-                        else
+                    }
+                    else
+                    {
+                        if (temp[2] != ((recvpacketcount + 1) % 0x100))
                         {
-                            packetslost += temp[2] - recvpacketcount;
+                            synclost++; // actualy sync loss's
+
+                            if (temp[2] < ((recvpacketcount + 1) % 0x100))
+                            {
+                                packetslost += 0x100 - recvpacketcount + temp[2];
+                            }
+                            else
+                            {
+                                packetslost += temp[2] - recvpacketcount;
+                            }
+
+                            log.InfoFormat("lost {0} pkts {1}", temp[2], (int)packetslost);
                         }
 
-                        log.InfoFormat("lost {0} pkts {1}", temp[2], (int)packetslost);
-                    }
+                        packetsnotlost++;
 
-                    packetsnotlost++;
+                        recvpacketcount = temp[2];
 
-                    recvpacketcount = temp[2];
+                    }
 
                     //MAVLINK_MSG_ID_GPS_STATUS
                     //if (temp[5] == MAVLINK_MSG_ID_GPS_STATUS)
@@ -2236,7 +2251,7 @@ namespace ArdupilotMega
 
                     try
                     {
-                        if (logfile != null)
+                        if (logfile != null && logfile.BaseStream.CanWrite)
                         {
                             lock (logwritelock)
                             {
@@ -2244,6 +2259,7 @@ namespace ArdupilotMega
                                 Array.Reverse(datearray);
                                 logfile.Write(datearray, 0, datearray.Length);
                                 logfile.Write(temp, 0, temp.Length);
+                                logfile.Flush();
                             }
                         }
 
@@ -2275,7 +2291,7 @@ namespace ArdupilotMega
 
                     if (buffer[5] == MAVLink.MAVLINK_MSG_ID_MISSION_ITEM)
                     {
-                        __mavlink_mission_item_t wp = buffer.ByteArrayToStructure<__mavlink_mission_item_t>(6);
+                        mavlink_mission_item_t wp = buffer.ByteArrayToStructure<mavlink_mission_item_t>(6);
 #else
 
             if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_COUNT)
@@ -2286,7 +2302,7 @@ namespace ArdupilotMega
 
             if (buffer[5] == MAVLink.MAVLINK_MSG_ID_WAYPOINT)
             {
-                __mavlink_waypoint_t wp = buffer.ByteArrayToStructure<__mavlink_waypoint_t>(6);
+                mavlink_waypoint_t wp = buffer.ByteArrayToStructure<mavlink_waypoint_t>(6);
 
 #endif
                 wps[wp.seq] = new PointLatLngAlt(wp.x, wp.y, wp.z, wp.seq.ToString());
@@ -2300,7 +2316,7 @@ namespace ArdupilotMega
             MainV2.giveComport = true;
 
             PointLatLngAlt plla = new PointLatLngAlt();
-            __mavlink_fence_fetch_point_t req = new __mavlink_fence_fetch_point_t();
+            mavlink_fence_fetch_point_t req = new mavlink_fence_fetch_point_t();
 
             req.idx = (byte)no;
             req.target_component = compid;
@@ -2335,7 +2351,7 @@ namespace ArdupilotMega
                     {
                         MainV2.giveComport = false;
 
-                        __mavlink_fence_point_t fp = buffer.ByteArrayToStructure<__mavlink_fence_point_t>(6);
+                        mavlink_fence_point_t fp = buffer.ByteArrayToStructure<mavlink_fence_point_t>(6);
 
                         plla.Lat = fp.lat;
                         plla.Lng = fp.lng;
@@ -2351,7 +2367,7 @@ namespace ArdupilotMega
 
         public bool setFencePoint(byte index, PointLatLngAlt plla, byte fencepointcount)
         {
-            __mavlink_fence_point_t fp = new __mavlink_fence_point_t();
+            mavlink_fence_point_t fp = new mavlink_fence_point_t();
 
             fp.idx = index;
             fp.count = fencepointcount;
diff --git a/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs b/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs
index 2f855af5681bb91f29bf73f0990168d0488ef027..ae36010847a5ccfdb762f050f0b1f8e7f60b5e7d 100644
--- a/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs
+++ b/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs
@@ -1,1460 +1,2376 @@
-using System;
-using System.Collections.Generic;
-using System.Text;
-using System.Runtime.InteropServices;
-
-namespace ArdupilotMega
-{
-#if MAVLINK10
-    partial class MAVLink
-    {
-
-        public const byte MAVLINK_MSG_ID_FENCED_POINT_LEN = 10;
-        public const byte MAVLINK_MSG_ID_FENCE_FETCH_POINT = 161;
-        [StructLayout(LayoutKind.Sequential, Pack = 1)]
-        public struct __mavlink_fence_fetch_point_t
-        {
-            public byte target_system; /// System ID
-            public byte target_component; /// Component ID
-            public byte idx; /// point index (first point is 1, 0 is for return point)
-        };
-
-        public const byte MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN = 3;
-        public const byte MAVLINK_MSG_ID_FENCE_POINT = 160;
-        [StructLayout(LayoutKind.Sequential, Pack = 1)]
-        public struct __mavlink_fence_point_t
-        {
-            public byte target_system; /// System ID
-            public byte target_component; /// Component ID
-            public byte idx; /// point index (first point is 1, 0 is for return point)
-            public byte count; /// total number of points (for sanity checking)
-            public float lat; /// Latitude of point
-            public float lng; /// Longitude of point
-        };
-
-		public byte[] MAVLINK_MESSAGE_LENGTHS = new byte[] {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 0, 0, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 4, 12, 15, 13, 6, 15, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 3};
-		public byte[] MAVLINK_MESSAGE_CRCS = new byte[] {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 0, 0, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 247};
-		public 		enum MAV_MOUNT_MODE
-		{
-			MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization | */
-			MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM. | */
-			MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */
-			MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */
-			MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */
-			MAV_MOUNT_MODE_ENUM_END=5, /*  | */
-		};
-
-		public 		enum MAV_CMD
-		{
-			WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude|  */
-			LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude|  */
-			LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude|  */
-			LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude|  */
-			RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty|  */
-			LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude|  */
-			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|  */
-			ROI=80, /* Sets the region of interest (ROI) for a sensor set or the
-		            vehicle itself. This can then be used by the vehicles control
-		            system to control the vehicle attitude and the attitude of various
-		            sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|  */
-			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|  */
-			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|  */
-			CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty|  */
-			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|  */
-			CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty|  */
-			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|  */
-			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|  */
-			DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty|  */
-			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|  */
-			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|  */
-			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|  */
-			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|  */
-			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|  */
-			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|  */
-			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|  */
-			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|  */
-			DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty|  */
-			DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)|  */
-			DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty|  */
-			DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty|  */
-			DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty|  */
-			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|  */
-			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|  */
-			PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units|  */
-			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|  */
-			PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty|  */
-			OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position|  */
-			MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item:  the last mission item to run (after this item is run, the mission ends)|  */
-			ENUM_END=301, /*  | */
-		};
-
-		public const byte MAVLINK_MSG_ID_AP_ADC = 153;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_ap_adc_t
-		{
-		 public ushort adc1; /// ADC output 1
-		 public ushort adc2; /// ADC output 2
-		 public ushort adc3; /// ADC output 3
-		 public ushort adc4; /// ADC output 4
-		 public ushort adc5; /// ADC output 5
-		 public ushort adc6; /// ADC output 6
-		};
-
-		public const byte MAVLINK_MSG_ID_AP_ADC_LEN = 12;
-		public const byte MAVLINK_MSG_ID_DIGICAM_CONFIGURE = 154;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_digicam_configure_t
-		{
-		public float extra_value; /// Correspondent value to given extra_param
-		 public ushort shutter_speed; /// Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public byte mode; /// Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
-		 public byte aperture; /// F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
-		 public byte iso; /// ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
-		 public byte exposure_type; /// Exposure type enumeration from 1 to N (0 means ignore)
-		 public byte command_id; /// Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
-		 public byte engine_cut_off; /// Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
-		 public byte extra_param; /// Extra parameters enumeration (0 means ignore)
-		};
-
-		public const byte MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN = 15;
-		public const byte MAVLINK_MSG_ID_DIGICAM_CONTROL = 155;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_digicam_control_t
-		{
-		public float extra_value; /// Correspondent value to given extra_param
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public byte session; /// 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
-		 public byte zoom_pos; /// 1 to N //Zoom's absolute position (0 means ignore)
-		 public byte zoom_step; /// -100 to 100 //Zooming step value to offset zoom from the current position
-		 public byte focus_lock; /// 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
-		 public byte shot; /// 0: ignore, 1: shot or start filming
-		 public byte command_id; /// Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
-		 public byte extra_param; /// Extra parameters enumeration (0 means ignore)
-		};
-
-		public const byte MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN = 13;
-		public const byte MAVLINK_MSG_ID_MEMINFO = 152;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_meminfo_t
-		{
-		 public ushort brkval; /// heap top
-		 public ushort freemem; /// free memory
-		};
-
-		public const byte MAVLINK_MSG_ID_MEMINFO_LEN = 4;
-		public const byte MAVLINK_MSG_ID_MOUNT_CONFIGURE = 156;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_mount_configure_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public byte mount_mode; /// mount operating mode (see MAV_MOUNT_MODE enum)
-		 public byte stab_roll; /// (1 = yes, 0 = no)
-		 public byte stab_pitch; /// (1 = yes, 0 = no)
-		 public byte stab_yaw; /// (1 = yes, 0 = no)
-		};
-
-		public const byte MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN = 6;
-		public const byte MAVLINK_MSG_ID_MOUNT_CONTROL = 157;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_mount_control_t
-		{
-		 public int input_a; /// pitch(deg*100) or lat, depending on mount mode
-		 public int input_b; /// roll(deg*100) or lon depending on mount mode
-		 public int input_c; /// yaw(deg*100) or alt (in cm) depending on mount mode
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public byte save_position; /// if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
-		};
-
-		public const byte MAVLINK_MSG_ID_MOUNT_CONTROL_LEN = 15;
-		public const byte MAVLINK_MSG_ID_MOUNT_STATUS = 158;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_mount_status_t
-		{
-		 public int pointing_a; /// pitch(deg*100) or lat, depending on mount mode
-		 public int pointing_b; /// roll(deg*100) or lon depending on mount mode
-		 public int pointing_c; /// yaw(deg*100) or alt (in cm) depending on mount mode
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		};
-
-		public const byte MAVLINK_MSG_ID_MOUNT_STATUS_LEN = 14;
-		public const byte MAVLINK_MSG_ID_SENSOR_OFFSETS = 150;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_sensor_offsets_t
-		{
-		public float mag_declination; /// magnetic declination (radians)
-		 public int raw_press; /// raw pressure from barometer
-		 public int raw_temp; /// raw temperature from barometer
-		public float gyro_cal_x; /// gyro X calibration
-		public float gyro_cal_y; /// gyro Y calibration
-		public float gyro_cal_z; /// gyro Z calibration
-		public float accel_cal_x; /// accel X calibration
-		public float accel_cal_y; /// accel Y calibration
-		public float accel_cal_z; /// accel Z calibration
-		 public short mag_ofs_x; /// magnetometer X offset
-		 public short mag_ofs_y; /// magnetometer Y offset
-		 public short mag_ofs_z; /// magnetometer Z offset
-		};
-
-		public const byte MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN = 42;
-		public const byte MAVLINK_MSG_ID_SET_MAG_OFFSETS = 151;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_set_mag_offsets_t
-		{
-		 public short mag_ofs_x; /// magnetometer X offset
-		 public short mag_ofs_y; /// magnetometer Y offset
-		 public short mag_ofs_z; /// magnetometer Z offset
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		};
-
-		public const byte MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN = 8;
-		public 		enum MAV_AUTOPILOT
-		{
-			MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */
-			MAV_AUTOPILOT_PIXHAWK=1, /* PIXHAWK autopilot, http://pixhawk.ethz.ch | */
-			MAV_AUTOPILOT_SLUGS=2, /* SLUGS autopilot, http://slugsuav.soe.ucsc.edu | */
-			MAV_AUTOPILOT_ARDUPILOTMEGA=3, /* ArduPilotMega / ArduCopter, http://diydrones.com | */
-			MAV_AUTOPILOT_OPENPILOT=4, /* OpenPilot, http://openpilot.org | */
-			MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY=5, /* Generic autopilot only supporting simple waypoints | */
-			MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, /* Generic autopilot supporting waypoints and other simple navigation commands | */
-			MAV_AUTOPILOT_GENERIC_MISSION_FULL=7, /* Generic autopilot supporting the full mission command set | */
-			MAV_AUTOPILOT_INVALID=8, /* No valid autopilot, e.g. a GCS or other MAVLink component | */
-			MAV_AUTOPILOT_PPZ=9, /* PPZ UAV - http://nongnu.org/paparazzi | */
-			MAV_AUTOPILOT_UDB=10, /* UAV Dev Board | */
-			MAV_AUTOPILOT_FP=11, /* FlexiPilot | */
-			MAV_AUTOPILOT_ENUM_END=12, /*  | */
-		};
-
-		public 		enum MAV_MODE_FLAG
-		{
-			MAV_MODE_FLAG_CUSTOM_MODE_ENABLED=1, /* 0b00000001 Reserved for future use. | */
-			MAV_MODE_FLAG_TEST_ENABLED=2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */
-			MAV_MODE_FLAG_AUTO_ENABLED=4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */
-			MAV_MODE_FLAG_GUIDED_ENABLED=8, /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */
-			MAV_MODE_FLAG_STABILIZE_ENABLED=16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */
-			MAV_MODE_FLAG_HIL_ENABLED=32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */
-			MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */
-			MAV_MODE_FLAG_SAFETY_ARMED=128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */
-			MAV_MODE_FLAG_ENUM_END=129, /*  | */
-		};
-
-		public 		enum MAV_MODE_FLAG_DECODE_POSITION
-		{
-			MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE=1, /* Eighth bit: 00000001 | */
-			MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */
-			MAV_MODE_FLAG_DECODE_POSITION_AUTO=4, /* Sixt bit:   00000100 | */
-			MAV_MODE_FLAG_DECODE_POSITION_GUIDED=8, /* Fifth bit:  00001000 | */
-			MAV_MODE_FLAG_DECODE_POSITION_STABILIZE=16, /* Fourth bit: 00010000 | */
-			MAV_MODE_FLAG_DECODE_POSITION_HIL=32, /* Third bit:  00100000 | */
-			MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64, /* Second bit: 01000000 | */
-			MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128, /* First bit:  10000000 | */
-			MAV_MODE_FLAG_DECODE_POSITION_ENUM_END=129, /*  | */
-		};
-
-		public 		enum MAV_GOTO
-		{
-			MAV_GOTO_DO_HOLD=0, /* Hold at the current position. | */
-			MAV_GOTO_DO_CONTINUE=1, /* Continue with the next item in mission execution. | */
-			MAV_GOTO_HOLD_AT_CURRENT_POSITION=2, /* Hold at the current position of the system | */
-			MAV_GOTO_HOLD_AT_SPECIFIED_POSITION=3, /* Hold at the position specified in the parameters of the DO_HOLD action | */
-			MAV_GOTO_ENUM_END=4, /*  | */
-		};
-
-		public 		enum MAV_MODE
-		{
-			MAV_MODE_PREFLIGHT=0, /* System is not ready to fly, booting, calibrating, etc. No flag is set. | */
-			MAV_MODE_MANUAL_DISARMED=64, /* System is allowed to be active, under manual (RC) control, no stabilization | */
-			MAV_MODE_TEST_DISARMED=66, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */
-			MAV_MODE_STABILIZE_DISARMED=80, /* System is allowed to be active, under assisted RC control. | */
-			MAV_MODE_GUIDED_DISARMED=88, /* System is allowed to be active, under autonomous control, manual setpoint | */
-			MAV_MODE_AUTO_DISARMED=92, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */
-			MAV_MODE_MANUAL_ARMED=192, /* System is allowed to be active, under manual (RC) control, no stabilization | */
-			MAV_MODE_TEST_ARMED=194, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */
-			MAV_MODE_STABILIZE_ARMED=208, /* System is allowed to be active, under assisted RC control. | */
-			MAV_MODE_GUIDED_ARMED=216, /* System is allowed to be active, under autonomous control, manual setpoint | */
-			MAV_MODE_AUTO_ARMED=220, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */
-			MAV_MODE_ENUM_END=221, /*  | */
-		};
-
-		public 		enum MAV_STATE
-		{
-			MAV_STATE_UNINIT=0, /* Uninitialized system, state is unknown. | */
-			MAV_STATE_BOOT=1, /* System is booting up. | */
-			MAV_STATE_CALIBRATING=2, /* System is calibrating and not flight-ready. | */
-			MAV_STATE_STANDBY=3, /* System is grounded and on standby. It can be launched any time. | */
-			MAV_STATE_ACTIVE=4, /* System is active and might be already airborne. Motors are engaged. | */
-			MAV_STATE_CRITICAL=5, /* System is in a non-normal flight mode. It can however still navigate. | */
-			MAV_STATE_EMERGENCY=6, /* System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | */
-			MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */
-			MAV_STATE_ENUM_END=8, /*  | */
-		};
-
-		public 		enum MAV_TYPE
-		{
-			MAV_TYPE_GENERIC=0, /* Generic micro air vehicle. | */
-			MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */
-			MAV_TYPE_QUADROTOR=2, /* Quadrotor | */
-			MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */
-			MAV_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */
-			MAV_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */
-			MAV_TYPE_GCS=6, /* Operator control unit / ground control station | */
-			MAV_TYPE_AIRSHIP=7, /* Airship, controlled | */
-			MAV_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */
-			MAV_TYPE_ROCKET=9, /* Rocket | */
-			MAV_TYPE_GROUND_ROVER=10, /* Ground rover | */
-			MAV_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */
-			MAV_TYPE_SUBMARINE=12, /* Submarine | */
-			MAV_TYPE_HEXAROTOR=13, /* Hexarotor | */
-			MAV_TYPE_OCTOROTOR=14, /* Octorotor | */
-			MAV_TYPE_TRICOPTER=15, /* Octorotor | */
-			MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */
-			MAV_TYPE_ENUM_END=17, /*  | */
-		};
-
-		public 		enum MAV_COMPONENT
-		{
-			MAV_COMP_ID_ALL=0, /*  | */
-			MAV_COMP_ID_CAMERA=100, /*  | */
-			MAV_COMP_ID_SERVO1=140, /*  | */
-			MAV_COMP_ID_SERVO2=141, /*  | */
-			MAV_COMP_ID_SERVO3=142, /*  | */
-			MAV_COMP_ID_SERVO4=143, /*  | */
-			MAV_COMP_ID_SERVO5=144, /*  | */
-			MAV_COMP_ID_SERVO6=145, /*  | */
-			MAV_COMP_ID_SERVO7=146, /*  | */
-			MAV_COMP_ID_SERVO8=147, /*  | */
-			MAV_COMP_ID_SERVO9=148, /*  | */
-			MAV_COMP_ID_SERVO10=149, /*  | */
-			MAV_COMP_ID_SERVO11=150, /*  | */
-			MAV_COMP_ID_SERVO12=151, /*  | */
-			MAV_COMP_ID_SERVO13=152, /*  | */
-			MAV_COMP_ID_SERVO14=153, /*  | */
-			MAV_COMP_ID_MAPPER=180, /*  | */
-			MAV_COMP_ID_MISSIONPLANNER=190, /*  | */
-			MAV_COMP_ID_PATHPLANNER=195, /*  | */
-			MAV_COMP_ID_IMU=200, /*  | */
-			MAV_COMP_ID_IMU_2=201, /*  | */
-			MAV_COMP_ID_IMU_3=202, /*  | */
-			MAV_COMP_ID_GPS=220, /*  | */
-			MAV_COMP_ID_UDP_BRIDGE=240, /*  | */
-			MAV_COMP_ID_UART_BRIDGE=241, /*  | */
-			MAV_COMP_ID_SYSTEM_CONTROL=250, /*  | */
-			MAV_COMPONENT_ENUM_END=251, /*  | */
-		};
-
-		public 		enum MAV_FRAME
-		{
-			MAV_FRAME_GLOBAL=0, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | */
-			MAV_FRAME_LOCAL_NED=1, /* Local coordinate frame, Z-up (x: north, y: east, z: down). | */
-			MAV_FRAME_MISSION=2, /* NOT a coordinate frame, indicates a mission command. | */
-			MAV_FRAME_GLOBAL_RELATIVE_ALT=3, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | */
-			MAV_FRAME_LOCAL_ENU=4, /* Local coordinate frame, Z-down (x: east, y: north, z: up) | */
-			MAV_FRAME_ENUM_END=5, /*  | */
-		};
-
-		public 		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=13, /*  | */
-		};
-
-		public 		enum MAV_ROI
-		{
-			MAV_ROI_NONE=0, /* No region of interest. | */
-			MAV_ROI_WPNEXT=1, /* Point toward next MISSION. | */
-			MAV_ROI_WPINDEX=2, /* Point toward given MISSION. | */
-			MAV_ROI_LOCATION=3, /* Point toward fixed location. | */
-			MAV_ROI_TARGET=4, /* Point toward of given id. | */
-			MAV_ROI_ENUM_END=5, /*  | */
-		};
-
-		public 		enum ACK
-		{
-			ACK_OK=1, /* Command / mission item is ok. | */
-			ACK_ERR_FAIL=2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | */
-			ACK_ERR_ACCESS_DENIED=3, /* The system is refusing to accept this command from this source / communication partner. | */
-			ACK_ERR_NOT_SUPPORTED=4, /* Command or mission item is not supported, other commands would be accepted. | */
-			ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED=5, /* The coordinate frame of this command / mission item is not supported. | */
-			ACK_ERR_COORDINATES_OUT_OF_RANGE=6, /* The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | */
-			ACK_ERR_X_LAT_OUT_OF_RANGE=7, /* The X or latitude value is out of range. | */
-			ACK_ERR_Y_LON_OUT_OF_RANGE=8, /* The Y or longitude value is out of range. | */
-			ACK_ERR_Z_ALT_OUT_OF_RANGE=9, /* The Z or altitude value is out of range. | */
-			ACK_ENUM_END=10, /*  | */
-		};
-
-		public 		enum MAV_VAR
-		{
-			MAV_VAR_FLOAT=0, /* 32 bit float | */
-			MAV_VAR_UINT8=1, /* 8 bit unsigned integer | */
-			MAV_VAR_INT8=2, /* 8 bit signed integer | */
-			MAV_VAR_UINT16=3, /* 16 bit unsigned integer | */
-			MAV_VAR_INT16=4, /* 16 bit signed integer | */
-			MAV_VAR_UINT32=5, /* 32 bit unsigned integer | */
-			MAV_VAR_INT32=6, /* 32 bit signed integer | */
-			MAV_VAR_ENUM_END=7, /*  | */
-		};
-
-		public 		enum MAV_RESULT
-		{
-			MAV_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */
-			MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */
-			MAV_RESULT_DENIED=2, /* Command PERMANENTLY DENIED | */
-			MAV_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */
-			MAV_RESULT_FAILED=4, /* Command executed, but failed | */
-			MAV_RESULT_ENUM_END=5, /*  | */
-		};
-
-		public 		enum MAV_MISSION_RESULT
-		{
-			MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */
-			MAV_MISSION_ERROR=1, /* generic error / not accepting mission commands at all right now | */
-			MAV_MISSION_UNSUPPORTED_FRAME=2, /* coordinate frame is not supported | */
-			MAV_MISSION_UNSUPPORTED=3, /* command is not supported | */
-			MAV_MISSION_NO_SPACE=4, /* mission item exceeds storage space | */
-			MAV_MISSION_INVALID=5, /* one of the parameters has an invalid value | */
-			MAV_MISSION_INVALID_PARAM1=6, /* param1 has an invalid value | */
-			MAV_MISSION_INVALID_PARAM2=7, /* param2 has an invalid value | */
-			MAV_MISSION_INVALID_PARAM3=8, /* param3 has an invalid value | */
-			MAV_MISSION_INVALID_PARAM4=9, /* param4 has an invalid value | */
-			MAV_MISSION_INVALID_PARAM5_X=10, /* x/param5 has an invalid value | */
-			MAV_MISSION_INVALID_PARAM6_Y=11, /* y/param6 has an invalid value | */
-			MAV_MISSION_INVALID_PARAM7=12, /* param7 has an invalid value | */
-			MAV_MISSION_INVALID_SEQUENCE=13, /* received waypoint out of sequence | */
-			MAV_MISSION_DENIED=14, /* not accepting any mission commands from this communication partner | */
-			MAV_MISSION_RESULT_ENUM_END=15, /*  | */
-		};
-
-		public const byte MAVLINK_MSG_ID_ATTITUDE = 30;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_attitude_t
-		{
-		 public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
-		public float roll; /// Roll angle (rad)
-		public float pitch; /// Pitch angle (rad)
-		public float yaw; /// Yaw angle (rad)
-		public float rollspeed; /// Roll angular speed (rad/s)
-		public float pitchspeed; /// Pitch angular speed (rad/s)
-		public float yawspeed; /// Yaw angular speed (rad/s)
-		};
-
-		public const byte MAVLINK_MSG_ID_ATTITUDE_LEN = 28;
-		public const byte MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_attitude_quaternion_t
-		{
-		 public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
-		public float q1; /// Quaternion component 1
-		public float q2; /// Quaternion component 2
-		public float q3; /// Quaternion component 3
-		public float q4; /// Quaternion component 4
-		public float rollspeed; /// Roll angular speed (rad/s)
-		public float pitchspeed; /// Pitch angular speed (rad/s)
-		public float yawspeed; /// Yaw angular speed (rad/s)
-		};
-
-		public const byte MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN = 32;
-		public const byte MAVLINK_MSG_ID_AUTH_KEY = 7;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_auth_key_t
-		{
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=32)] 
-		 public byte[] key; /// key
-		};
-
-		public const byte MAVLINK_MSG_ID_AUTH_KEY_LEN = 32;
-		public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_change_operator_control_t
-		{
-		 public byte target_system; /// System the GCS requests control for
-		 public byte control_request; /// 0: request control of this MAV, 1: Release control of this MAV
-		 public byte 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.
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=25)] 
-		 public byte[] 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 "!?,.-"
-		};
-
-		public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN = 28;
-		public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_change_operator_control_ack_t
-		{
-		 public byte gcs_system_id; /// ID of the GCS this message 
-		 public byte control_request; /// 0: request control of this MAV, 1: Release control of this MAV
-		 public byte ack; /// 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
-		};
-
-		public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN = 3;
-		public const byte MAVLINK_MSG_ID_COMMAND_ACK = 77;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_command_ack_t
-		{
-		 public ushort command; /// Command ID, as defined by MAV_CMD enum.
-		 public byte result; /// See MAV_RESULT enum
-		};
-
-		public const byte MAVLINK_MSG_ID_COMMAND_ACK_LEN = 3;
-		public const byte MAVLINK_MSG_ID_COMMAND_LONG = 76;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_command_long_t
-		{
-		public float param1; /// Parameter 1, as defined by MAV_CMD enum.
-		public float param2; /// Parameter 2, as defined by MAV_CMD enum.
-		public float param3; /// Parameter 3, as defined by MAV_CMD enum.
-		public float param4; /// Parameter 4, as defined by MAV_CMD enum.
-		public float param5; /// Parameter 5, as defined by MAV_CMD enum.
-		public float param6; /// Parameter 6, as defined by MAV_CMD enum.
-		public float param7; /// Parameter 7, as defined by MAV_CMD enum.
-		 public ushort command; /// Command ID, as defined by MAV_CMD enum.
-		 public byte target_system; /// System which should execute the command
-		 public byte target_component; /// Component which should execute the command, 0 for all components
-		 public byte confirmation; /// 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
-		};
-
-		public const byte MAVLINK_MSG_ID_COMMAND_LONG_LEN = 33;
-		public const byte MAVLINK_MSG_ID_DATA_STREAM = 67;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_data_stream_t
-		{
-		 public ushort message_rate; /// The requested interval between two messages of this type
-		 public byte stream_id; /// The ID of the requested data stream
-		 public byte on_off; /// 1 stream is enabled, 0 stream is stopped.
-		};
-
-		public const byte MAVLINK_MSG_ID_DATA_STREAM_LEN = 4;
-		public const byte MAVLINK_MSG_ID_DEBUG = 254;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_debug_t
-		{
-		 public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
-		public float value; /// DEBUG value
-		 public byte ind; /// index of debug variable
-		};
-
-		public const byte MAVLINK_MSG_ID_DEBUG_LEN = 9;
-		public const byte MAVLINK_MSG_ID_DEBUG_VECT = 250;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_debug_vect_t
-		{
-		 public ulong time_usec; /// Timestamp
-		public float x; /// x
-		public float y; /// y
-		public float z; /// z
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=10)] 
-		 public byte[] name; /// Name
-		};
-
-		public const byte MAVLINK_MSG_ID_DEBUG_VECT_LEN = 30;
-		public const byte MAVLINK_MSG_ID_EXTENDED_MESSAGE = 255;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_extended_message_t
-		{
-		 public byte target_system; /// System which should execute the command
-		 public byte target_component; /// Component which should execute the command, 0 for all components
-		 public byte protocol_flags; /// Retransmission / ACK flags
-		};
-
-		public const byte MAVLINK_MSG_ID_EXTENDED_MESSAGE_LEN = 3;
-		public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_global_position_int_t
-		{
-		 public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
-		 public int lat; /// Latitude, expressed as * 1E7
-		 public int lon; /// Longitude, expressed as * 1E7
-		 public int alt; /// Altitude in meters, expressed as * 1000 (millimeters), above MSL
-		 public int relative_alt; /// Altitude above ground in meters, expressed as * 1000 (millimeters)
-		 public short vx; /// Ground X Speed (Latitude), expressed as m/s * 100
-		 public short vy; /// Ground Y Speed (Longitude), expressed as m/s * 100
-		 public short vz; /// Ground Z Speed (Altitude), expressed as m/s * 100
-		 public ushort hdg; /// Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
-		};
-
-		public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN = 28;
-		public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT = 52;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_global_position_setpoint_int_t
-		{
-		 public int latitude; /// WGS84 Latitude position in degrees * 1E7
-		 public int longitude; /// WGS84 Longitude position in degrees * 1E7
-		 public int altitude; /// WGS84 Altitude in meters * 1000 (positive for up)
-		 public short yaw; /// Desired yaw angle in degrees * 100
-		 public byte coordinate_frame; /// Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
-		};
-
-		public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN = 15;
-		public const byte MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_global_vision_position_estimate_t
-		{
-		 public ulong usec; /// Timestamp (milliseconds)
-		public float x; /// Global X position
-		public float y; /// Global Y position
-		public float z; /// Global Z position
-		public float roll; /// Roll angle in rad
-		public float pitch; /// Pitch angle in rad
-		public float yaw; /// Yaw angle in rad
-		};
-
-		public const byte MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN = 32;
-		public const byte MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_gps_global_origin_t
-		{
-		 public int latitude; /// Latitude (WGS84), expressed as * 1E7
-		 public int longitude; /// Longitude (WGS84), expressed as * 1E7
-		 public int altitude; /// Altitude(WGS84), expressed as * 1000
-		};
-
-		public const byte MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN = 12;
-		public const byte MAVLINK_MSG_ID_GPS_RAW_INT = 24;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_gps_raw_int_t
-		{
-		 public ulong time_usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
-		 public int lat; /// Latitude in 1E7 degrees
-		 public int lon; /// Longitude in 1E7 degrees
-		 public int alt; /// Altitude in 1E3 meters (millimeters) above MSL
-		 public ushort eph; /// GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
-		 public ushort epv; /// GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
-		 public ushort vel; /// GPS ground speed (m/s * 100). If unknown, set to: 65535
-		 public ushort cog; /// Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
-		 public byte 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.
-		 public byte satellites_visible; /// Number of satellites visible. If unknown, set to 255
-		};
-
-		public const byte MAVLINK_MSG_ID_GPS_RAW_INT_LEN = 30;
-		public const byte MAVLINK_MSG_ID_GPS_STATUS = 25;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_gps_status_t
-		{
-		 public byte satellites_visible; /// Number of satellites visible
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=20)] 
-		 public byte[] satellite_prn; /// Global satellite ID
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=20)] 
-		 public byte[] satellite_used; /// 0: Satellite not used, 1: used for localization
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=20)] 
-		 public byte[] satellite_elevation; /// Elevation (0: right on top of receiver, 90: on the horizon) of satellite
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=20)] 
-		 public byte[] satellite_azimuth; /// Direction of satellite, 0: 0 deg, 255: 360 deg.
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=20)] 
-		 public byte[] satellite_snr; /// Signal to noise ratio of satellite
-		};
-
-		public const byte MAVLINK_MSG_ID_GPS_STATUS_LEN = 101;
-		public const byte MAVLINK_MSG_ID_HEARTBEAT = 0;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_heartbeat_t
-		{
-		 public uint custom_mode; /// Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific.
-		 public byte type; /// Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
-		 public byte autopilot; /// Autopilot type / class. defined in MAV_CLASS ENUM
-		 public byte base_mode; /// System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
-		 public byte system_status; /// System status flag, see MAV_STATUS ENUM
-		 public byte mavlink_version; /// MAVLink version
-		};
-
-		public const byte MAVLINK_MSG_ID_HEARTBEAT_LEN = 9;
-		public const byte MAVLINK_MSG_ID_HIL_CONTROLS = 91;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_hil_controls_t
-		{
-		 public ulong time_usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
-		public float roll_ailerons; /// Control output -1 .. 1
-		public float pitch_elevator; /// Control output -1 .. 1
-		public float yaw_rudder; /// Control output -1 .. 1
-		public float throttle; /// Throttle 0 .. 1
-		public float aux1; /// Aux 1, -1 .. 1
-		public float aux2; /// Aux 2, -1 .. 1
-		public float aux3; /// Aux 3, -1 .. 1
-		public float aux4; /// Aux 4, -1 .. 1
-		 public byte mode; /// System mode (MAV_MODE)
-		 public byte nav_mode; /// Navigation mode (MAV_NAV_MODE)
-		};
-
-		public const byte MAVLINK_MSG_ID_HIL_CONTROLS_LEN = 42;
-		public const byte MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_hil_rc_inputs_raw_t
-		{
-		 public ulong time_usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
-		 public ushort chan1_raw; /// RC channel 1 value, in microseconds
-		 public ushort chan2_raw; /// RC channel 2 value, in microseconds
-		 public ushort chan3_raw; /// RC channel 3 value, in microseconds
-		 public ushort chan4_raw; /// RC channel 4 value, in microseconds
-		 public ushort chan5_raw; /// RC channel 5 value, in microseconds
-		 public ushort chan6_raw; /// RC channel 6 value, in microseconds
-		 public ushort chan7_raw; /// RC channel 7 value, in microseconds
-		 public ushort chan8_raw; /// RC channel 8 value, in microseconds
-		 public ushort chan9_raw; /// RC channel 9 value, in microseconds
-		 public ushort chan10_raw; /// RC channel 10 value, in microseconds
-		 public ushort chan11_raw; /// RC channel 11 value, in microseconds
-		 public ushort chan12_raw; /// RC channel 12 value, in microseconds
-		 public byte rssi; /// Receive signal strength indicator, 0: 0%, 255: 100%
-		};
-
-		public const byte MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN = 33;
-		public const byte MAVLINK_MSG_ID_HIL_STATE = 90;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_hil_state_t
-		{
-		 public ulong time_usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
-		public float roll; /// Roll angle (rad)
-		public float pitch; /// Pitch angle (rad)
-		public float yaw; /// Yaw angle (rad)
-		public float rollspeed; /// Roll angular speed (rad/s)
-		public float pitchspeed; /// Pitch angular speed (rad/s)
-		public float yawspeed; /// Yaw angular speed (rad/s)
-		 public int lat; /// Latitude, expressed as * 1E7
-		 public int lon; /// Longitude, expressed as * 1E7
-		 public int alt; /// Altitude in meters, expressed as * 1000 (millimeters)
-		 public short vx; /// Ground X Speed (Latitude), expressed as m/s * 100
-		 public short vy; /// Ground Y Speed (Longitude), expressed as m/s * 100
-		 public short vz; /// Ground Z Speed (Altitude), expressed as m/s * 100
-		 public short xacc; /// X acceleration (mg)
-		 public short yacc; /// Y acceleration (mg)
-		 public short zacc; /// Z acceleration (mg)
-		};
-
-		public const byte MAVLINK_MSG_ID_HIL_STATE_LEN = 56;
-		public const byte MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_local_position_ned_t
-		{
-		 public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
-		public float x; /// X Position
-		public float y; /// Y Position
-		public float z; /// Z Position
-		public float vx; /// X Speed
-		public float vy; /// Y Speed
-		public float vz; /// Z Speed
-		};
-
-		public const byte MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN = 28;
-		public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT = 51;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_local_position_setpoint_t
-		{
-		public float x; /// x position
-		public float y; /// y position
-		public float z; /// z position
-		public float yaw; /// Desired yaw angle
-		 public byte coordinate_frame; /// Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
-		};
-
-		public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN = 17;
-		public const byte MAVLINK_MSG_ID_MANUAL_CONTROL = 69;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_manual_control_t
-		{
-		public float roll; /// roll
-		public float pitch; /// pitch
-		public float yaw; /// yaw
-		public float thrust; /// thrust
-		 public byte target; /// The system to be controlled
-		 public byte roll_manual; /// roll control enabled auto:0, manual:1
-		 public byte pitch_manual; /// pitch auto:0, manual:1
-		 public byte yaw_manual; /// yaw auto:0, manual:1
-		 public byte thrust_manual; /// thrust auto:0, manual:1
-		};
-
-		public const byte MAVLINK_MSG_ID_MANUAL_CONTROL_LEN = 21;
-		public const byte MAVLINK_MSG_ID_MEMORY_VECT = 249;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_memory_vect_t
-		{
-		 public ushort address; /// Starting address of the debug variables
-		 public byte ver; /// Version code of the type variable. 0=unknown, type ignored and assumed public short. 1=as below
-		 public byte type; /// Type code of the memory variables. for ver = 1: 0=16 x public short, 1=16 x public ushort, 2=16 x Q15, 3=16 x 1Q14
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=32)] 
-		 public byte[] value; /// Memory contents at specified address
-		};
-
-		public const byte MAVLINK_MSG_ID_MEMORY_VECT_LEN = 36;
-		public const byte MAVLINK_MSG_ID_MISSION_ACK = 47;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_mission_ack_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public byte type; /// See MAV_MISSION_RESULT enum
-		};
-
-		public const byte MAVLINK_MSG_ID_MISSION_ACK_LEN = 3;
-		public const byte MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_mission_clear_all_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		};
-
-		public const byte MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN = 2;
-		public const byte MAVLINK_MSG_ID_MISSION_COUNT = 44;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_mission_count_t
-		{
-		 public ushort count; /// Number of mission items in the sequence
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		};
-
-		public const byte MAVLINK_MSG_ID_MISSION_COUNT_LEN = 4;
-		public const byte MAVLINK_MSG_ID_MISSION_CURRENT = 42;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_mission_current_t
-		{
-		 public ushort seq; /// Sequence
-		};
-
-		public const byte MAVLINK_MSG_ID_MISSION_CURRENT_LEN = 2;
-		public const byte MAVLINK_MSG_ID_MISSION_ITEM = 39;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_mission_item_t
-		{
-		public float param1; /// PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters
-		public float param2; /// PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
-		public float param3; /// PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
-		public float param4; /// PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH
-		public float x; /// PARAM5 / local: x position, global: latitude
-		public float y; /// PARAM6 / y position: global: longitude
-		public float z; /// PARAM7 / z position: global: altitude
-		 public ushort seq; /// Sequence
-		 public ushort command; /// The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public byte frame; /// The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
-		 public byte current; /// false:0, true:1
-		 public byte autocontinue; /// autocontinue to next wp
-		};
-
-		public const byte MAVLINK_MSG_ID_MISSION_ITEM_LEN = 37;
-		public const byte MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_mission_item_reached_t
-		{
-		 public ushort seq; /// Sequence
-		};
-
-		public const byte MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN = 2;
-		public const byte MAVLINK_MSG_ID_MISSION_REQUEST = 40;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_mission_request_t
-		{
-		 public ushort seq; /// Sequence
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		};
-
-		public const byte MAVLINK_MSG_ID_MISSION_REQUEST_LEN = 4;
-		public const byte MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_mission_request_list_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		};
-
-		public const byte MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN = 2;
-		public const byte MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_mission_request_partial_list_t
-		{
-		 public short start_index; /// Start index, 0 by default
-		 public short end_index; /// End index, -1 by default (-1: send list to end). Else a valid index of the list
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		};
-
-		public const byte MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN = 6;
-		public const byte MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_mission_set_current_t
-		{
-		 public ushort seq; /// Sequence
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		};
-
-		public const byte MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN = 4;
-		public const byte MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_mission_write_partial_list_t
-		{
-		 public short start_index; /// Start index, 0 by default and smaller / equal to the largest index of the current onboard list.
-		 public short end_index; /// End index, equal or greater than start index.
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		};
-
-		public const byte MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN = 6;
-		public const byte MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_named_value_float_t
-		{
-		 public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
-		public float value; /// Floating point value
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=10)] 
-		 public byte[] name; /// Name of the debug variable
-		};
-
-		public const byte MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN = 18;
-		public const byte MAVLINK_MSG_ID_NAMED_VALUE_INT = 252;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_named_value_int_t
-		{
-		 public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
-		 public int value; /// Signed integer value
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=10)] 
-		 public byte[] name; /// Name of the debug variable
-		};
-
-		public const byte MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN = 18;
-		public const byte MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_nav_controller_output_t
-		{
-		public float nav_roll; /// Current desired roll in degrees
-		public float nav_pitch; /// Current desired pitch in degrees
-		public float alt_error; /// Current altitude error in meters
-		public float aspd_error; /// Current airspeed error in meters/second
-		public float xtrack_error; /// Current crosstrack error on x-y plane in meters
-		 public short nav_bearing; /// Current desired heading in degrees
-		 public short target_bearing; /// Bearing to current MISSION/target in degrees
-		 public ushort wp_dist; /// Distance to active MISSION in meters
-		};
-
-		public const byte MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN = 26;
-		public const byte MAVLINK_MSG_ID_OPTICAL_FLOW = 100;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_optical_flow_t
-		{
-		 public ulong time_usec; /// Timestamp (UNIX)
-		public float ground_distance; /// Ground distance in meters
-		 public short flow_x; /// Flow in pixels in x-sensor direction
-		 public short flow_y; /// Flow in pixels in y-sensor direction
-		 public byte sensor_id; /// Sensor ID
-		 public byte quality; /// Optical flow quality / confidence. 0: bad, 255: maximum quality
-		};
-
-		public const byte MAVLINK_MSG_ID_OPTICAL_FLOW_LEN = 18;
-		public const byte MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_param_request_list_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		};
-
-		public const byte MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN = 2;
-		public const byte MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_param_request_read_t
-		{
-		 public short param_index; /// Parameter index. Send -1 to use the param ID field as identifier
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=16)] 
-		 public byte[] param_id; /// Onboard parameter id
-		};
-
-		public const byte MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN = 20;
-		public const byte MAVLINK_MSG_ID_PARAM_SET = 23;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_param_set_t
-		{
-		public float param_value; /// Onboard parameter value
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=16)] 
-		 public byte[] param_id; /// Onboard parameter id
-		 public byte param_type; /// Onboard parameter type: see MAV_VAR enum
-		};
-
-		public const byte MAVLINK_MSG_ID_PARAM_SET_LEN = 23;
-		public const byte MAVLINK_MSG_ID_PARAM_VALUE = 22;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_param_value_t
-		{
-		public float param_value; /// Onboard parameter value
-		 public ushort param_count; /// Total number of onboard parameters
-		 public ushort param_index; /// Index of this onboard parameter
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=16)] 
-		 public byte[] param_id; /// Onboard parameter id
-		 public byte param_type; /// Onboard parameter type: see MAV_VAR enum
-		};
-
-		public const byte MAVLINK_MSG_ID_PARAM_VALUE_LEN = 25;
-		public const byte MAVLINK_MSG_ID_PING = 4;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_ping_t
-		{
-		 public ulong time_usec; /// Unix timestamp in microseconds
-		 public uint seq; /// PING sequence
-		 public byte 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
-		 public byte 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
-		};
-
-		public const byte MAVLINK_MSG_ID_PING_LEN = 14;
-		public const byte MAVLINK_MSG_ID_RAW_IMU = 27;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_raw_imu_t
-		{
-		 public ulong time_usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
-		 public short xacc; /// X acceleration (raw)
-		 public short yacc; /// Y acceleration (raw)
-		 public short zacc; /// Z acceleration (raw)
-		 public short xgyro; /// Angular speed around X axis (raw)
-		 public short ygyro; /// Angular speed around Y axis (raw)
-		 public short zgyro; /// Angular speed around Z axis (raw)
-		 public short xmag; /// X Magnetic field (raw)
-		 public short ymag; /// Y Magnetic field (raw)
-		 public short zmag; /// Z Magnetic field (raw)
-		};
-
-		public const byte MAVLINK_MSG_ID_RAW_IMU_LEN = 26;
-		public const byte MAVLINK_MSG_ID_RAW_PRESSURE = 28;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_raw_pressure_t
-		{
-		 public ulong time_usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
-		 public short press_abs; /// Absolute pressure (raw)
-		 public short press_diff1; /// Differential pressure 1 (raw)
-		 public short press_diff2; /// Differential pressure 2 (raw)
-		 public short temperature; /// Raw Temperature measurement (raw)
-		};
-
-		public const byte MAVLINK_MSG_ID_RAW_PRESSURE_LEN = 16;
-		public const byte MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_rc_channels_override_t
-		{
-		 public ushort chan1_raw; /// RC channel 1 value, in microseconds
-		 public ushort chan2_raw; /// RC channel 2 value, in microseconds
-		 public ushort chan3_raw; /// RC channel 3 value, in microseconds
-		 public ushort chan4_raw; /// RC channel 4 value, in microseconds
-		 public ushort chan5_raw; /// RC channel 5 value, in microseconds
-		 public ushort chan6_raw; /// RC channel 6 value, in microseconds
-		 public ushort chan7_raw; /// RC channel 7 value, in microseconds
-		 public ushort chan8_raw; /// RC channel 8 value, in microseconds
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		};
-
-		public const byte MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN = 18;
-		public const byte MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_rc_channels_raw_t
-		{
-		 public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
-		 public ushort chan1_raw; /// RC channel 1 value, in microseconds
-		 public ushort chan2_raw; /// RC channel 2 value, in microseconds
-		 public ushort chan3_raw; /// RC channel 3 value, in microseconds
-		 public ushort chan4_raw; /// RC channel 4 value, in microseconds
-		 public ushort chan5_raw; /// RC channel 5 value, in microseconds
-		 public ushort chan6_raw; /// RC channel 6 value, in microseconds
-		 public ushort chan7_raw; /// RC channel 7 value, in microseconds
-		 public ushort chan8_raw; /// RC channel 8 value, in microseconds
-		 public byte port; /// Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
-		 public byte rssi; /// Receive signal strength indicator, 0: 0%, 255: 100%
-		};
-
-		public const byte MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN = 22;
-		public const byte MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_rc_channels_scaled_t
-		{
-		 public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
-		 public short chan1_scaled; /// RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
-		 public short chan2_scaled; /// RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
-		 public short chan3_scaled; /// RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
-		 public short chan4_scaled; /// RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
-		 public short chan5_scaled; /// RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
-		 public short chan6_scaled; /// RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
-		 public short chan7_scaled; /// RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
-		 public short chan8_scaled; /// RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
-		 public byte port; /// Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
-		 public byte rssi; /// Receive signal strength indicator, 0: 0%, 255: 100%
-		};
-
-		public const byte MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN = 22;
-		public const byte MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_request_data_stream_t
-		{
-		 public ushort req_message_rate; /// The requested interval between two messages of this type
-		 public byte target_system; /// The target requested to send the message stream.
-		 public byte target_component; /// The target requested to send the message stream.
-		 public byte req_stream_id; /// The ID of the requested data stream
-		 public byte start_stop; /// 1 to start sending, 0 to stop sending.
-		};
-
-		public const byte MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN = 6;
-		public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT = 59;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t
-		{
-		 public uint time_boot_ms; /// Timestamp in milliseconds since system boot
-		public float roll_speed; /// Desired roll angular speed in rad/s
-		public float pitch_speed; /// Desired pitch angular speed in rad/s
-		public float yaw_speed; /// Desired yaw angular speed in rad/s
-		public float thrust; /// Collective thrust, normalized to 0 .. 1
-		};
-
-		public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN = 20;
-		public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT = 58;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_roll_pitch_yaw_thrust_setpoint_t
-		{
-		 public uint time_boot_ms; /// Timestamp in milliseconds since system boot
-		public float roll; /// Desired roll angle in radians
-		public float pitch; /// Desired pitch angle in radians
-		public float yaw; /// Desired yaw angle in radians
-		public float thrust; /// Collective thrust, normalized to 0 .. 1
-		};
-
-		public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN = 20;
-		public const byte MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_safety_allowed_area_t
-		{
-		public float p1x; /// x position 1 / Latitude 1
-		public float p1y; /// y position 1 / Longitude 1
-		public float p1z; /// z position 1 / Altitude 1
-		public float p2x; /// x position 2 / Latitude 2
-		public float p2y; /// y position 2 / Longitude 2
-		public float p2z; /// z position 2 / Altitude 2
-		 public byte 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.
-		};
-
-		public const byte MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN = 25;
-		public const byte MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_safety_set_allowed_area_t
-		{
-		public float p1x; /// x position 1 / Latitude 1
-		public float p1y; /// y position 1 / Longitude 1
-		public float p1z; /// z position 1 / Altitude 1
-		public float p2x; /// x position 2 / Latitude 2
-		public float p2y; /// y position 2 / Longitude 2
-		public float p2z; /// z position 2 / Altitude 2
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public byte 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.
-		};
-
-		public const byte MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN = 27;
-		public const byte MAVLINK_MSG_ID_SCALED_IMU = 26;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_scaled_imu_t
-		{
-		 public uint time_boot_ms; /// Timestamp (milliseconds since system boot)
-		 public short xacc; /// X acceleration (mg)
-		 public short yacc; /// Y acceleration (mg)
-		 public short zacc; /// Z acceleration (mg)
-		 public short xgyro; /// Angular speed around X axis (millirad /sec)
-		 public short ygyro; /// Angular speed around Y axis (millirad /sec)
-		 public short zgyro; /// Angular speed around Z axis (millirad /sec)
-		 public short xmag; /// X Magnetic field (milli tesla)
-		 public short ymag; /// Y Magnetic field (milli tesla)
-		 public short zmag; /// Z Magnetic field (milli tesla)
-		};
-
-		public const byte MAVLINK_MSG_ID_SCALED_IMU_LEN = 22;
-		public const byte MAVLINK_MSG_ID_SCALED_PRESSURE = 29;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_scaled_pressure_t
-		{
-		 public uint time_boot_ms; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
-		public float press_abs; /// Absolute pressure (hectopascal)
-		public float press_diff; /// Differential pressure 1 (hectopascal)
-		 public short temperature; /// Temperature measurement (0.01 degrees celsius)
-		};
-
-		public const byte MAVLINK_MSG_ID_SCALED_PRESSURE_LEN = 14;
-		public const byte MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_servo_output_raw_t
-		{
-		 public uint time_usec; /// Timestamp (since UNIX epoch or microseconds since system boot)
-		 public ushort servo1_raw; /// Servo output 1 value, in microseconds
-		 public ushort servo2_raw; /// Servo output 2 value, in microseconds
-		 public ushort servo3_raw; /// Servo output 3 value, in microseconds
-		 public ushort servo4_raw; /// Servo output 4 value, in microseconds
-		 public ushort servo5_raw; /// Servo output 5 value, in microseconds
-		 public ushort servo6_raw; /// Servo output 6 value, in microseconds
-		 public ushort servo7_raw; /// Servo output 7 value, in microseconds
-		 public ushort servo8_raw; /// Servo output 8 value, in microseconds
-		 public byte port; /// Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
-		};
-
-		public const byte MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN = 21;
-		public const byte MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT = 53;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_set_global_position_setpoint_int_t
-		{
-		 public int latitude; /// WGS84 Latitude position in degrees * 1E7
-		 public int longitude; /// WGS84 Longitude position in degrees * 1E7
-		 public int altitude; /// WGS84 Altitude in meters * 1000 (positive for up)
-		 public short yaw; /// Desired yaw angle in degrees * 100
-		 public byte coordinate_frame; /// Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
-		};
-
-		public const byte MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN = 15;
-		public const byte MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_set_gps_global_origin_t
-		{
-		 public int latitude; /// global position * 1E7
-		 public int longitude; /// global position * 1E7
-		 public int altitude; /// global position * 1000
-		 public byte target_system; /// System ID
-		};
-
-		public const byte MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN = 13;
-		public const byte MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT = 50;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_set_local_position_setpoint_t
-		{
-		public float x; /// x position
-		public float y; /// y position
-		public float z; /// z position
-		public float yaw; /// Desired yaw angle
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public byte coordinate_frame; /// Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
-		};
-
-		public const byte MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN = 19;
-		public const byte MAVLINK_MSG_ID_SET_MODE = 11;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_set_mode_t
-		{
-		 public uint custom_mode; /// The new autopilot-specific mode. This field can be ignored by an autopilot.
-		 public byte target_system; /// The system setting the mode
-		 public byte base_mode; /// The new base mode
-		};
-
-		public const byte MAVLINK_MSG_ID_SET_MODE_LEN = 6;
-		public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST = 57;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_set_roll_pitch_yaw_speed_thrust_t
-		{
-		public float roll_speed; /// Desired roll angular speed in rad/s
-		public float pitch_speed; /// Desired pitch angular speed in rad/s
-		public float yaw_speed; /// Desired yaw angular speed in rad/s
-		public float thrust; /// Collective thrust, normalized to 0 .. 1
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		};
-
-		public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN = 18;
-		public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST = 56;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_set_roll_pitch_yaw_thrust_t
-		{
-		public float roll; /// Desired roll angle in radians
-		public float pitch; /// Desired pitch angle in radians
-		public float yaw; /// Desired yaw angle in radians
-		public float thrust; /// Collective thrust, normalized to 0 .. 1
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		};
-
-		public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN = 18;
-		public const byte MAVLINK_MSG_ID_STATE_CORRECTION = 64;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_state_correction_t
-		{
-		public float xErr; /// x position error
-		public float yErr; /// y position error
-		public float zErr; /// z position error
-		public float rollErr; /// roll error (radians)
-		public float pitchErr; /// pitch error (radians)
-		public float yawErr; /// yaw error (radians)
-		public float vxErr; /// x velocity
-		public float vyErr; /// y velocity
-		public float vzErr; /// z velocity
-		};
-
-		public const byte MAVLINK_MSG_ID_STATE_CORRECTION_LEN = 36;
-		public const byte MAVLINK_MSG_ID_STATUSTEXT = 253;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_statustext_t
-		{
-		 public byte severity; /// Severity of status, 0 = info message, 255 = critical fault
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=50)] 
-		 public byte[] text; /// Status text message, without null termination character
-		};
-
-		public const byte MAVLINK_MSG_ID_STATUSTEXT_LEN = 51;
-		public const byte MAVLINK_MSG_ID_SYSTEM_TIME = 2;
-		public const byte MAVLINK_MSG_ID_SYS_STATUS = 1;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_sys_status_t
-		{
-		 public uint onboard_control_sensors_present; /// Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
-		 public uint onboard_control_sensors_enabled; /// Bitmask showing which onboard controllers and sensors are enabled:  Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
-		 public uint onboard_control_sensors_health; /// Bitmask showing which onboard controllers and sensors are operational or have an error:  Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
-		 public ushort load; /// Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
-		 public ushort voltage_battery; /// Battery voltage, in millivolts (1 = 1 millivolt)
-		 public short current_battery; /// Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
-		 public ushort drop_rate_comm; /// Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
-		 public ushort errors_comm; /// Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
-		 public ushort errors_count1; /// Autopilot-specific errors
-		 public ushort errors_count2; /// Autopilot-specific errors
-		 public ushort errors_count3; /// Autopilot-specific errors
-		 public ushort errors_count4; /// Autopilot-specific errors
-		 public byte battery_remaining; /// Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
-		};
-
-		public const byte MAVLINK_MSG_ID_SYS_STATUS_LEN = 31;
-		public const byte MAVLINK_MSG_ID_VFR_HUD = 74;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_vfr_hud_t
-		{
-		public float airspeed; /// Current airspeed in m/s
-		public float groundspeed; /// Current ground speed in m/s
-		public float alt; /// Current altitude (MSL), in meters
-		public float climb; /// Current climb rate in meters/second
-		 public short heading; /// Current heading in degrees, in compass units (0..360, 0=north)
-		 public ushort throttle; /// Current throttle setting in integer percent, 0 to 100
-		};
-
-		public const byte MAVLINK_MSG_ID_VFR_HUD_LEN = 20;
-		public const byte MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_vicon_position_estimate_t
-		{
-		 public ulong usec; /// Timestamp (milliseconds)
-		public float x; /// Global X position
-		public float y; /// Global Y position
-		public float z; /// Global Z position
-		public float roll; /// Roll angle in rad
-		public float pitch; /// Pitch angle in rad
-		public float yaw; /// Yaw angle in rad
-		};
-
-		public const byte MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN = 32;
-		public const byte MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_vision_position_estimate_t
-		{
-		 public ulong usec; /// Timestamp (milliseconds)
-		public float x; /// Global X position
-		public float y; /// Global Y position
-		public float z; /// Global Z position
-		public float roll; /// Roll angle in rad
-		public float pitch; /// Pitch angle in rad
-		public float yaw; /// Yaw angle in rad
-		};
-
-		public const byte MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN = 32;
-		public const byte MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_vision_speed_estimate_t
-		{
-		 public ulong usec; /// Timestamp (milliseconds)
-		public float x; /// Global X speed
-		public float y; /// Global Y speed
-		public float z; /// Global Z speed
-		};
-
-		public const byte MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN = 20;
-		public 		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
-		};
-
-Type[] mavstructs = new Type[] {typeof( __mavlink_heartbeat_t) ,typeof( __mavlink_sys_status_t) ,null ,null ,typeof( __mavlink_ping_t) ,typeof( __mavlink_change_operator_control_t) ,typeof( __mavlink_change_operator_control_ack_t) ,typeof( __mavlink_auth_key_t) ,null ,null ,null ,typeof( __mavlink_set_mode_t) ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_param_request_read_t) ,typeof( __mavlink_param_request_list_t) ,typeof( __mavlink_param_value_t) ,typeof( __mavlink_param_set_t) ,typeof( __mavlink_gps_raw_int_t) ,typeof( __mavlink_gps_status_t) ,typeof( __mavlink_scaled_imu_t) ,typeof( __mavlink_raw_imu_t) ,typeof( __mavlink_raw_pressure_t) ,typeof( __mavlink_scaled_pressure_t) ,typeof( __mavlink_attitude_t) ,typeof( __mavlink_attitude_quaternion_t) ,typeof( __mavlink_local_position_ned_t) ,typeof( __mavlink_global_position_int_t) ,typeof( __mavlink_rc_channels_scaled_t) ,typeof( __mavlink_rc_channels_raw_t) ,typeof( __mavlink_servo_output_raw_t) ,typeof( __mavlink_mission_request_partial_list_t) ,typeof( __mavlink_mission_write_partial_list_t) ,typeof( __mavlink_mission_item_t) ,typeof( __mavlink_mission_request_t) ,typeof( __mavlink_mission_set_current_t) ,typeof( __mavlink_mission_current_t) ,typeof( __mavlink_mission_request_list_t) ,typeof( __mavlink_mission_count_t) ,typeof( __mavlink_mission_clear_all_t) ,typeof( __mavlink_mission_item_reached_t) ,typeof( __mavlink_mission_ack_t) ,typeof( __mavlink_set_gps_global_origin_t) ,typeof( __mavlink_gps_global_origin_t) ,typeof( __mavlink_set_local_position_setpoint_t) ,typeof( __mavlink_local_position_setpoint_t) ,typeof( __mavlink_global_position_setpoint_int_t) ,typeof( __mavlink_set_global_position_setpoint_int_t) ,typeof( __mavlink_safety_set_allowed_area_t) ,typeof( __mavlink_safety_allowed_area_t) ,typeof( __mavlink_set_roll_pitch_yaw_thrust_t) ,typeof( __mavlink_set_roll_pitch_yaw_speed_thrust_t) ,typeof( __mavlink_roll_pitch_yaw_thrust_setpoint_t) ,typeof( __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t) ,null ,null ,typeof( __mavlink_nav_controller_output_t) ,null ,typeof( __mavlink_state_correction_t) ,null ,typeof( __mavlink_request_data_stream_t) ,typeof( __mavlink_data_stream_t) ,null ,typeof( __mavlink_manual_control_t) ,typeof( __mavlink_rc_channels_override_t) ,null ,null ,null ,typeof( __mavlink_vfr_hud_t) ,null ,typeof( __mavlink_command_long_t) ,typeof( __mavlink_command_ack_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_hil_state_t) ,typeof( __mavlink_hil_controls_t) ,typeof( __mavlink_hil_rc_inputs_raw_t) ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_optical_flow_t) ,typeof( __mavlink_global_vision_position_estimate_t) ,typeof( __mavlink_vision_position_estimate_t) ,typeof( __mavlink_vision_speed_estimate_t) ,typeof( __mavlink_vicon_position_estimate_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_sensor_offsets_t) ,typeof( __mavlink_set_mag_offsets_t) ,typeof( __mavlink_meminfo_t) ,typeof( __mavlink_ap_adc_t) ,typeof( __mavlink_digicam_configure_t) ,typeof( __mavlink_digicam_control_t) ,typeof( __mavlink_mount_configure_t) ,typeof( __mavlink_mount_control_t) ,typeof( __mavlink_mount_status_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_memory_vect_t) ,typeof( __mavlink_debug_vect_t) ,typeof( __mavlink_named_value_float_t) ,typeof( __mavlink_named_value_int_t) ,typeof( __mavlink_statustext_t) ,typeof( __mavlink_debug_t) ,typeof( __mavlink_extended_message_t) ,null ,};
-
-	}
-	#endif
-}
-
+using System;
+using System.Collections.Generic;
+using System.Text;
+using System.Runtime.InteropServices;
+
+namespace ArdupilotMega
+{
+#if MAVLINK10
+    partial class MAVLink
+    {
+        public const string MAVLINK_BUILD_DATE = "Sun Apr  8 12:29:46 2012";
+        public const string MAVLINK_WIRE_PROTOCOL_VERSION = "1.0";
+        public const int MAVLINK_MAX_DIALECT_PAYLOAD_SIZE = 42;
+
+        public const int MAVLINK_LITTLE_ENDIAN = 1;
+        public const int MAVLINK_BIG_ENDIAN = 0;
+
+        public const byte MAVLINK_STX = 254;
+
+        public const byte MAVLINK_ENDIAN = MAVLINK_LITTLE_ENDIAN;
+
+        public const bool MAVLINK_ALIGNED_FIELDS = (1 == 1);
+
+        public const byte MAVLINK_CRC_EXTRA = 1;
+        
+        public const bool MAVLINK_NEED_BYTE_SWAP = (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN);
+        
+        public byte[] MAVLINK_MESSAGE_LENGTHS = new byte[] {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 0, 0, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 3};
+
+        public byte[] MAVLINK_MESSAGE_CRCS = new byte[] {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 0, 0, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 42, 21, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 247};
+
+        public Type[] MAVLINK_MESSAGE_INFO = new Type[] {typeof( mavlink_heartbeat_t ), typeof( mavlink_sys_status_t ), typeof( mavlink_system_time_t ), null, typeof( mavlink_ping_t ), typeof( mavlink_change_operator_control_t ), typeof( mavlink_change_operator_control_ack_t ), typeof( mavlink_auth_key_t ), null, null, null, typeof( mavlink_set_mode_t ), null, null, null, null, null, null, null, null, typeof( mavlink_param_request_read_t ), typeof( mavlink_param_request_list_t ), typeof( mavlink_param_value_t ), typeof( mavlink_param_set_t ), typeof( mavlink_gps_raw_int_t ), typeof( mavlink_gps_status_t ), typeof( mavlink_scaled_imu_t ), typeof( mavlink_raw_imu_t ), typeof( mavlink_raw_pressure_t ), typeof( mavlink_scaled_pressure_t ), typeof( mavlink_attitude_t ), typeof( mavlink_attitude_quaternion_t ), typeof( mavlink_local_position_ned_t ), typeof( mavlink_global_position_int_t ), typeof( mavlink_rc_channels_scaled_t ), typeof( mavlink_rc_channels_raw_t ), typeof( mavlink_servo_output_raw_t ), typeof( mavlink_mission_request_partial_list_t ), typeof( mavlink_mission_write_partial_list_t ), typeof( mavlink_mission_item_t ), typeof( mavlink_mission_request_t ), typeof( mavlink_mission_set_current_t ), typeof( mavlink_mission_current_t ), typeof( mavlink_mission_request_list_t ), typeof( mavlink_mission_count_t ), typeof( mavlink_mission_clear_all_t ), typeof( mavlink_mission_item_reached_t ), typeof( mavlink_mission_ack_t ), typeof( mavlink_set_gps_global_origin_t ), typeof( mavlink_gps_global_origin_t ), typeof( mavlink_set_local_position_setpoint_t ), typeof( mavlink_local_position_setpoint_t ), typeof( mavlink_global_position_setpoint_int_t ), typeof( mavlink_set_global_position_setpoint_int_t ), typeof( mavlink_safety_set_allowed_area_t ), typeof( mavlink_safety_allowed_area_t ), typeof( mavlink_set_roll_pitch_yaw_thrust_t ), typeof( mavlink_set_roll_pitch_yaw_speed_thrust_t ), typeof( mavlink_roll_pitch_yaw_thrust_setpoint_t ), typeof( mavlink_roll_pitch_yaw_speed_thrust_setpoint_t ), null, null, typeof( mavlink_nav_controller_output_t ), null, typeof( mavlink_state_correction_t ), null, typeof( mavlink_request_data_stream_t ), typeof( mavlink_data_stream_t ), null, typeof( mavlink_manual_control_t ), typeof( mavlink_rc_channels_override_t ), null, null, null, typeof( mavlink_vfr_hud_t ), null, typeof( mavlink_command_long_t ), typeof( mavlink_command_ack_t ), null, null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_hil_state_t ), typeof( mavlink_hil_controls_t ), typeof( mavlink_hil_rc_inputs_raw_t ), null, null, null, null, null, null, null, typeof( mavlink_optical_flow_t ), typeof( mavlink_global_vision_position_estimate_t ), typeof( mavlink_vision_position_estimate_t ), typeof( mavlink_vision_speed_estimate_t ), typeof( mavlink_vicon_position_estimate_t ), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_sensor_offsets_t ), typeof( mavlink_set_mag_offsets_t ), typeof( mavlink_meminfo_t ), typeof( mavlink_ap_adc_t ), typeof( mavlink_digicam_configure_t ), typeof( mavlink_digicam_control_t ), typeof( mavlink_mount_configure_t ), typeof( mavlink_mount_control_t ), typeof( mavlink_mount_status_t ), null, typeof( mavlink_fence_point_t ), typeof( mavlink_fence_fetch_point_t ), typeof( mavlink_fence_status_t ), typeof( mavlink_ahrs_t ), typeof( mavlink_simstate_t ), typeof( mavlink_hwstatus_t ), typeof( mavlink_radio_t ), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_memory_vect_t ), typeof( mavlink_debug_vect_t ), typeof( mavlink_named_value_float_t ), typeof( mavlink_named_value_int_t ), typeof( mavlink_statustext_t ), typeof( mavlink_debug_t ), typeof( mavlink_extended_message_t )};
+
+        public const byte MAVLINK_VERSION = 2;
+    
+        
+        /** @brief Enumeration of possible mount operation modes */
+        public enum MAV_MOUNT_MODE
+        {
+    	///<summary> Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization | </summary>
+            RETRACT=0, 
+        	///<summary> Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM. | </summary>
+            NEUTRAL=1, 
+        	///<summary> Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | </summary>
+            MAVLINK_TARGETING=2, 
+        	///<summary> Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | </summary>
+            RC_TARGETING=3, 
+        	///<summary> Load neutral position and start to point to Lat,Lon,Alt | </summary>
+            GPS_POINT=4, 
+        	///<summary>  | </summary>
+            ENUM_END=5, 
+        
+        };
+        
+        /** @brief  */
+        public enum MAV_CMD
+        {
+    	///<summary> Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude|  </summary>
+            NAV_WAYPOINT=16, 
+        	///<summary> Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude|  </summary>
+            NAV_LOITER_UNLIM=17, 
+        	///<summary> Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude|  </summary>
+            NAV_LOITER_TURNS=18, 
+        	///<summary> Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude|  </summary>
+            NAV_LOITER_TIME=19, 
+        	///<summary> Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty|  </summary>
+            NAV_RETURN_TO_LAUNCH=20, 
+        	///<summary> Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude|  </summary>
+            NAV_LAND=21, 
+        	///<summary> 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|  </summary>
+            NAV_TAKEOFF=22, 
+        	///<summary> Sets the region of interest (ROI) for a sensor set or the             vehicle itself. This can then be used by the vehicles control             system to control the vehicle attitude and the attitude of various             sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|  </summary>
+            NAV_ROI=80, 
+        	///<summary> 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|  </summary>
+            NAV_PATHPLANNING=81, 
+        	///<summary> 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|  </summary>
+            NAV_LAST=95, 
+        	///<summary> Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty|  </summary>
+            CONDITION_DELAY=112, 
+        	///<summary> Ascend/descend at rate.  Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude|  </summary>
+            CONDITION_CHANGE_ALT=113, 
+        	///<summary> Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty|  </summary>
+            CONDITION_DISTANCE=114, 
+        	///<summary> 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|  </summary>
+            CONDITION_YAW=115, 
+        	///<summary> 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|  </summary>
+            CONDITION_LAST=159, 
+        	///<summary> Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty|  </summary>
+            DO_SET_MODE=176, 
+        	///<summary> 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|  </summary>
+            DO_JUMP=177, 
+        	///<summary> 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|  </summary>
+            DO_CHANGE_SPEED=178, 
+        	///<summary> 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|  </summary>
+            DO_SET_HOME=179, 
+        	///<summary> 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|  </summary>
+            DO_SET_PARAMETER=180, 
+        	///<summary> Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty|  </summary>
+            DO_SET_RELAY=181, 
+        	///<summary> 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|  </summary>
+            DO_REPEAT_RELAY=182, 
+        	///<summary> Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty|  </summary>
+            DO_SET_SERVO=183, 
+        	///<summary> 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|  </summary>
+            DO_REPEAT_SERVO=184, 
+        	///<summary> Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty|  </summary>
+            DO_CONTROL_VIDEO=200, 
+        	///<summary> Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)|  </summary>
+            DO_DIGICAM_CONFIGURE=202, 
+        	///<summary> Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty|  </summary>
+            DO_DIGICAM_CONTROL=203, 
+        	///<summary> Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty|  </summary>
+            DO_MOUNT_CONFIGURE=204, 
+        	///<summary> Mission command to control a camera or antenna mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty|  </summary>
+            DO_MOUNT_CONTROL=205, 
+        	///<summary> 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|  </summary>
+            DO_LAST=240, 
+        	///<summary> 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|  </summary>
+            PREFLIGHT_CALIBRATION=241, 
+        	///<summary> Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units|  </summary>
+            PREFLIGHT_SET_SENSOR_OFFSETS=242, 
+        	///<summary> 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|  </summary>
+            PREFLIGHT_STORAGE=245, 
+        	///<summary> Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty|  </summary>
+            PREFLIGHT_REBOOT_SHUTDOWN=246, 
+        	///<summary> Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position|  </summary>
+            OVERRIDE_GOTO=252, 
+        	///<summary> start running a mission |first_item: the first mission item to run| last_item:  the last mission item to run (after this item is run, the mission ends)|  </summary>
+            MISSION_START=300, 
+        	///<summary>  | </summary>
+            ENUM_END=301, 
+        
+        };
+        
+        /** @brief  */
+        public enum FENCE_ACTION
+        {
+    	///<summary> Disable fenced mode | </summary>
+            NONE=0, 
+        	///<summary> Switched to guided mode to return point (fence point 0) | </summary>
+            GUIDED=1, 
+        	///<summary>  | </summary>
+            ENUM_END=2, 
+        
+        };
+        
+        /** @brief  */
+        public enum FENCE_BREACH
+        {
+    	///<summary> No last fence breach | </summary>
+            NONE=0, 
+        	///<summary> Breached minimum altitude | </summary>
+            MINALT=1, 
+        	///<summary> Breached minimum altitude | </summary>
+            MAXALT=2, 
+        	///<summary> Breached fence boundary | </summary>
+            BOUNDARY=3, 
+        	///<summary>  | </summary>
+            ENUM_END=4, 
+        
+        };
+        
+    
+        
+        /** @brief Micro air vehicle / autopilot classes. This identifies the individual model. */
+        public enum MAV_AUTOPILOT
+        {
+    	///<summary> Generic autopilot, full support for everything | </summary>
+            GENERIC=0, 
+        	///<summary> PIXHAWK autopilot, http://pixhawk.ethz.ch | </summary>
+            PIXHAWK=1, 
+        	///<summary> SLUGS autopilot, http://slugsuav.soe.ucsc.edu | </summary>
+            SLUGS=2, 
+        	///<summary> ArduPilotMega / ArduCopter, http://diydrones.com | </summary>
+            ARDUPILOTMEGA=3, 
+        	///<summary> OpenPilot, http://openpilot.org | </summary>
+            OPENPILOT=4, 
+        	///<summary> Generic autopilot only supporting simple waypoints | </summary>
+            GENERIC_WAYPOINTS_ONLY=5, 
+        	///<summary> Generic autopilot supporting waypoints and other simple navigation commands | </summary>
+            GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, 
+        	///<summary> Generic autopilot supporting the full mission command set | </summary>
+            GENERIC_MISSION_FULL=7, 
+        	///<summary> No valid autopilot, e.g. a GCS or other MAVLink component | </summary>
+            INVALID=8, 
+        	///<summary> PPZ UAV - http://nongnu.org/paparazzi | </summary>
+            PPZ=9, 
+        	///<summary> UAV Dev Board | </summary>
+            UDB=10, 
+        	///<summary> FlexiPilot | </summary>
+            FP=11, 
+        	///<summary>  | </summary>
+            ENUM_END=12, 
+        
+        };
+        
+        /** @brief These flags encode the MAV mode. */
+        public enum MAV_MODE_FLAG
+        {
+    	///<summary> 0b00000001 Reserved for future use. | </summary>
+            CUSTOM_MODE_ENABLED=1, 
+        	///<summary> 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | </summary>
+            TEST_ENABLED=2, 
+        	///<summary> 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | </summary>
+            AUTO_ENABLED=4, 
+        	///<summary> 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | </summary>
+            GUIDED_ENABLED=8, 
+        	///<summary> 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | </summary>
+            STABILIZE_ENABLED=16, 
+        	///<summary> 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | </summary>
+            HIL_ENABLED=32, 
+        	///<summary> 0b01000000 remote control input is enabled. | </summary>
+            MANUAL_INPUT_ENABLED=64, 
+        	///<summary> 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | </summary>
+            SAFETY_ARMED=128, 
+        	///<summary>  | </summary>
+            ENUM_END=129, 
+        
+        };
+        
+        /** @brief These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. */
+        public enum MAV_MODE_FLAG_DECODE_POSITION
+        {
+    	///<summary> Eighth bit: 00000001 | </summary>
+            CUSTOM_MODE=1, 
+        	///<summary> Seventh bit: 00000010 | </summary>
+            TEST=2, 
+        	///<summary> Sixt bit:   00000100 | </summary>
+            AUTO=4, 
+        	///<summary> Fifth bit:  00001000 | </summary>
+            GUIDED=8, 
+        	///<summary> Fourth bit: 00010000 | </summary>
+            STABILIZE=16, 
+        	///<summary> Third bit:  00100000 | </summary>
+            HIL=32, 
+        	///<summary> Second bit: 01000000 | </summary>
+            MANUAL=64, 
+        	///<summary> First bit:  10000000 | </summary>
+            SAFETY=128, 
+        	///<summary>  | </summary>
+            ENUM_END=129, 
+        
+        };
+        
+        /** @brief Override command, pauses current mission execution and moves immediately to a position */
+        public enum MAV_GOTO
+        {
+    	///<summary> Hold at the current position. | </summary>
+            DO_HOLD=0, 
+        	///<summary> Continue with the next item in mission execution. | </summary>
+            DO_CONTINUE=1, 
+        	///<summary> Hold at the current position of the system | </summary>
+            HOLD_AT_CURRENT_POSITION=2, 
+        	///<summary> Hold at the position specified in the parameters of the DO_HOLD action | </summary>
+            HOLD_AT_SPECIFIED_POSITION=3, 
+        	///<summary>  | </summary>
+            ENUM_END=4, 
+        
+        };
+        
+        /** @brief These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it                simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. */
+        public enum MAV_MODE
+        {
+    	///<summary> System is not ready to fly, booting, calibrating, etc. No flag is set. | </summary>
+            PREFLIGHT=0, 
+        	///<summary> System is allowed to be active, under manual (RC) control, no stabilization | </summary>
+            MANUAL_DISARMED=64, 
+        	///<summary> UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | </summary>
+            TEST_DISARMED=66, 
+        	///<summary> System is allowed to be active, under assisted RC control. | </summary>
+            STABILIZE_DISARMED=80, 
+        	///<summary> System is allowed to be active, under autonomous control, manual setpoint | </summary>
+            GUIDED_DISARMED=88, 
+        	///<summary> System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | </summary>
+            AUTO_DISARMED=92, 
+        	///<summary> System is allowed to be active, under manual (RC) control, no stabilization | </summary>
+            MANUAL_ARMED=192, 
+        	///<summary> UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | </summary>
+            TEST_ARMED=194, 
+        	///<summary> System is allowed to be active, under assisted RC control. | </summary>
+            STABILIZE_ARMED=208, 
+        	///<summary> System is allowed to be active, under autonomous control, manual setpoint | </summary>
+            GUIDED_ARMED=216, 
+        	///<summary> System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | </summary>
+            AUTO_ARMED=220, 
+        	///<summary>  | </summary>
+            ENUM_END=221, 
+        
+        };
+        
+        /** @brief  */
+        public enum MAV_STATE
+        {
+    	///<summary> Uninitialized system, state is unknown. | </summary>
+            UNINIT=0, 
+        	///<summary> System is booting up. | </summary>
+            BOOT=1, 
+        	///<summary> System is calibrating and not flight-ready. | </summary>
+            CALIBRATING=2, 
+        	///<summary> System is grounded and on standby. It can be launched any time. | </summary>
+            STANDBY=3, 
+        	///<summary> System is active and might be already airborne. Motors are engaged. | </summary>
+            ACTIVE=4, 
+        	///<summary> System is in a non-normal flight mode. It can however still navigate. | </summary>
+            CRITICAL=5, 
+        	///<summary> System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | </summary>
+            EMERGENCY=6, 
+        	///<summary> System just initialized its power-down sequence, will shut down now. | </summary>
+            POWEROFF=7, 
+        	///<summary>  | </summary>
+            ENUM_END=8, 
+        
+        };
+        
+        /** @brief  */
+        public enum MAV_TYPE
+        {
+    	///<summary> Generic micro air vehicle. | </summary>
+            GENERIC=0, 
+        	///<summary> Fixed wing aircraft. | </summary>
+            FIXED_WING=1, 
+        	///<summary> Quadrotor | </summary>
+            QUADROTOR=2, 
+        	///<summary> Coaxial helicopter | </summary>
+            COAXIAL=3, 
+        	///<summary> Normal helicopter with tail rotor. | </summary>
+            HELICOPTER=4, 
+        	///<summary> Ground installation | </summary>
+            ANTENNA_TRACKER=5, 
+        	///<summary> Operator control unit / ground control station | </summary>
+            GCS=6, 
+        	///<summary> Airship, controlled | </summary>
+            AIRSHIP=7, 
+        	///<summary> Free balloon, uncontrolled | </summary>
+            FREE_BALLOON=8, 
+        	///<summary> Rocket | </summary>
+            ROCKET=9, 
+        	///<summary> Ground rover | </summary>
+            GROUND_ROVER=10, 
+        	///<summary> Surface vessel, boat, ship | </summary>
+            SURFACE_BOAT=11, 
+        	///<summary> Submarine | </summary>
+            SUBMARINE=12, 
+        	///<summary> Hexarotor | </summary>
+            HEXAROTOR=13, 
+        	///<summary> Octorotor | </summary>
+            OCTOROTOR=14, 
+        	///<summary> Octorotor | </summary>
+            TRICOPTER=15, 
+        	///<summary> Flapping wing | </summary>
+            FLAPPING_WING=16, 
+        	///<summary>  | </summary>
+            ENUM_END=17, 
+        
+        };
+        
+        /** @brief  */
+        public enum MAV_COMPONENT
+        {
+    	///<summary>  | </summary>
+            MAV_COMP_ID_ALL=0, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_CAMERA=100, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_SERVO1=140, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_SERVO2=141, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_SERVO3=142, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_SERVO4=143, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_SERVO5=144, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_SERVO6=145, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_SERVO7=146, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_SERVO8=147, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_SERVO9=148, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_SERVO10=149, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_SERVO11=150, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_SERVO12=151, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_SERVO13=152, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_SERVO14=153, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_MAPPER=180, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_MISSIONPLANNER=190, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_PATHPLANNER=195, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_IMU=200, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_IMU_2=201, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_IMU_3=202, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_GPS=220, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_UDP_BRIDGE=240, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_UART_BRIDGE=241, 
+        	///<summary>  | </summary>
+            MAV_COMP_ID_SYSTEM_CONTROL=250, 
+        	///<summary>  | </summary>
+            ENUM_END=251, 
+        
+        };
+        
+        /** @brief  */
+        public enum MAV_FRAME
+        {
+    	///<summary> Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | </summary>
+            GLOBAL=0, 
+        	///<summary> Local coordinate frame, Z-up (x: north, y: east, z: down). | </summary>
+            LOCAL_NED=1, 
+        	///<summary> NOT a coordinate frame, indicates a mission command. | </summary>
+            MISSION=2, 
+        	///<summary> Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | </summary>
+            GLOBAL_RELATIVE_ALT=3, 
+        	///<summary> Local coordinate frame, Z-down (x: east, y: north, z: up) | </summary>
+            LOCAL_ENU=4, 
+        	///<summary>  | </summary>
+            ENUM_END=5, 
+        
+        };
+        
+        /** @brief  */
+        public enum MAVLINK_DATA_STREAM_TYPE
+        {
+    	///<summary>  | </summary>
+            MAVLINK_DATA_STREAM_IMG_JPEG=1, 
+        	///<summary>  | </summary>
+            MAVLINK_DATA_STREAM_IMG_BMP=2, 
+        	///<summary>  | </summary>
+            MAVLINK_DATA_STREAM_IMG_RAW8U=3, 
+        	///<summary>  | </summary>
+            MAVLINK_DATA_STREAM_IMG_RAW32U=4, 
+        	///<summary>  | </summary>
+            MAVLINK_DATA_STREAM_IMG_PGM=5, 
+        	///<summary>  | </summary>
+            MAVLINK_DATA_STREAM_IMG_PNG=6, 
+        	///<summary>  | </summary>
+            ENUM_END=7, 
+        
+        };
+        
+        /** @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.       */
+        public enum MAV_DATA_STREAM
+        {
+    	///<summary> Enable all data streams | </summary>
+            ALL=0, 
+        	///<summary> Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | </summary>
+            RAW_SENSORS=1, 
+        	///<summary> Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | </summary>
+            EXTENDED_STATUS=2, 
+        	///<summary> Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | </summary>
+            RC_CHANNELS=3, 
+        	///<summary> Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | </summary>
+            RAW_CONTROLLER=4, 
+        	///<summary> Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | </summary>
+            POSITION=6, 
+        	///<summary> Dependent on the autopilot | </summary>
+            EXTRA1=10, 
+        	///<summary> Dependent on the autopilot | </summary>
+            EXTRA2=11, 
+        	///<summary> Dependent on the autopilot | </summary>
+            EXTRA3=12, 
+        	///<summary>  | </summary>
+            ENUM_END=13, 
+        
+        };
+        
+        /** @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).              */
+        public enum MAV_ROI
+        {
+    	///<summary> No region of interest. | </summary>
+            NONE=0, 
+        	///<summary> Point toward next MISSION. | </summary>
+            WPNEXT=1, 
+        	///<summary> Point toward given MISSION. | </summary>
+            WPINDEX=2, 
+        	///<summary> Point toward fixed location. | </summary>
+            LOCATION=3, 
+        	///<summary> Point toward of given id. | </summary>
+            TARGET=4, 
+        	///<summary>  | </summary>
+            ENUM_END=5, 
+        
+        };
+        
+        /** @brief ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. */
+        public enum MAV_CMD_ACK
+        {
+    	///<summary> Command / mission item is ok. | </summary>
+            OK=1, 
+        	///<summary> Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | </summary>
+            ERR_FAIL=2, 
+        	///<summary> The system is refusing to accept this command from this source / communication partner. | </summary>
+            ERR_ACCESS_DENIED=3, 
+        	///<summary> Command or mission item is not supported, other commands would be accepted. | </summary>
+            ERR_NOT_SUPPORTED=4, 
+        	///<summary> The coordinate frame of this command / mission item is not supported. | </summary>
+            ERR_COORDINATE_FRAME_NOT_SUPPORTED=5, 
+        	///<summary> The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | </summary>
+            ERR_COORDINATES_OUT_OF_RANGE=6, 
+        	///<summary> The X or latitude value is out of range. | </summary>
+            ERR_X_LAT_OUT_OF_RANGE=7, 
+        	///<summary> The Y or longitude value is out of range. | </summary>
+            ERR_Y_LON_OUT_OF_RANGE=8, 
+        	///<summary> The Z or altitude value is out of range. | </summary>
+            ERR_Z_ALT_OUT_OF_RANGE=9, 
+        	///<summary>  | </summary>
+            ENUM_END=10, 
+        
+        };
+        
+        /** @brief type of a mavlink parameter */
+        public enum MAV_VAR
+        {
+    	///<summary> 32 bit float | </summary>
+            FLOAT=0, 
+        	///<summary> 8 bit unsigned integer | </summary>
+            UINT8=1, 
+        	///<summary> 8 bit signed integer | </summary>
+            INT8=2, 
+        	///<summary> 16 bit unsigned integer | </summary>
+            UINT16=3, 
+        	///<summary> 16 bit signed integer | </summary>
+            INT16=4, 
+        	///<summary> 32 bit unsigned integer | </summary>
+            UINT32=5, 
+        	///<summary> 32 bit signed integer | </summary>
+            INT32=6, 
+        	///<summary>  | </summary>
+            ENUM_END=7, 
+        
+        };
+        
+        /** @brief result from a mavlink command */
+        public enum MAV_RESULT
+        {
+    	///<summary> Command ACCEPTED and EXECUTED | </summary>
+            ACCEPTED=0, 
+        	///<summary> Command TEMPORARY REJECTED/DENIED | </summary>
+            TEMPORARILY_REJECTED=1, 
+        	///<summary> Command PERMANENTLY DENIED | </summary>
+            DENIED=2, 
+        	///<summary> Command UNKNOWN/UNSUPPORTED | </summary>
+            UNSUPPORTED=3, 
+        	///<summary> Command executed, but failed | </summary>
+            FAILED=4, 
+        	///<summary>  | </summary>
+            ENUM_END=5, 
+        
+        };
+        
+        /** @brief result in a mavlink mission ack */
+        public enum MAV_MISSION_RESULT
+        {
+    	///<summary> mission accepted OK | </summary>
+            MAV_MISSION_ACCEPTED=0, 
+        	///<summary> generic error / not accepting mission commands at all right now | </summary>
+            MAV_MISSION_ERROR=1, 
+        	///<summary> coordinate frame is not supported | </summary>
+            MAV_MISSION_UNSUPPORTED_FRAME=2, 
+        	///<summary> command is not supported | </summary>
+            MAV_MISSION_UNSUPPORTED=3, 
+        	///<summary> mission item exceeds storage space | </summary>
+            MAV_MISSION_NO_SPACE=4, 
+        	///<summary> one of the parameters has an invalid value | </summary>
+            MAV_MISSION_INVALID=5, 
+        	///<summary> param1 has an invalid value | </summary>
+            MAV_MISSION_INVALID_PARAM1=6, 
+        	///<summary> param2 has an invalid value | </summary>
+            MAV_MISSION_INVALID_PARAM2=7, 
+        	///<summary> param3 has an invalid value | </summary>
+            MAV_MISSION_INVALID_PARAM3=8, 
+        	///<summary> param4 has an invalid value | </summary>
+            MAV_MISSION_INVALID_PARAM4=9, 
+        	///<summary> x/param5 has an invalid value | </summary>
+            MAV_MISSION_INVALID_PARAM5_X=10, 
+        	///<summary> y/param6 has an invalid value | </summary>
+            MAV_MISSION_INVALID_PARAM6_Y=11, 
+        	///<summary> param7 has an invalid value | </summary>
+            MAV_MISSION_INVALID_PARAM7=12, 
+        	///<summary> received waypoint out of sequence | </summary>
+            MAV_MISSION_INVALID_SEQUENCE=13, 
+        	///<summary> not accepting any mission commands from this communication partner | </summary>
+            MAV_MISSION_DENIED=14, 
+        	///<summary>  | </summary>
+            ENUM_END=15, 
+        
+        };
+        
+
+    public const byte MAVLINK_MSG_ID_SENSOR_OFFSETS = 150;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)]
+    public struct mavlink_sensor_offsets_t
+    {
+        /// <summary> magnetic declination (radians) </summary>
+        public  Single mag_declination;
+            /// <summary> raw pressure from barometer </summary>
+        public  Int32 raw_press;
+            /// <summary> raw temperature from barometer </summary>
+        public  Int32 raw_temp;
+            /// <summary> gyro X calibration </summary>
+        public  Single gyro_cal_x;
+            /// <summary> gyro Y calibration </summary>
+        public  Single gyro_cal_y;
+            /// <summary> gyro Z calibration </summary>
+        public  Single gyro_cal_z;
+            /// <summary> accel X calibration </summary>
+        public  Single accel_cal_x;
+            /// <summary> accel Y calibration </summary>
+        public  Single accel_cal_y;
+            /// <summary> accel Z calibration </summary>
+        public  Single accel_cal_z;
+            /// <summary> magnetometer X offset </summary>
+        public  Int16 mag_ofs_x;
+            /// <summary> magnetometer Y offset </summary>
+        public  Int16 mag_ofs_y;
+            /// <summary> magnetometer Z offset </summary>
+        public  Int16 mag_ofs_z;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SET_MAG_OFFSETS = 151;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)]
+    public struct mavlink_set_mag_offsets_t
+    {
+        /// <summary> magnetometer X offset </summary>
+        public  Int16 mag_ofs_x;
+            /// <summary> magnetometer Y offset </summary>
+        public  Int16 mag_ofs_y;
+            /// <summary> magnetometer Z offset </summary>
+        public  Int16 mag_ofs_z;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MEMINFO = 152;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)]
+    public struct mavlink_meminfo_t
+    {
+        /// <summary> heap top </summary>
+        public  UInt16 brkval;
+            /// <summary> free memory </summary>
+        public  UInt16 freemem;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_AP_ADC = 153;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)]
+    public struct mavlink_ap_adc_t
+    {
+        /// <summary> ADC output 1 </summary>
+        public  UInt16 adc1;
+            /// <summary> ADC output 2 </summary>
+        public  UInt16 adc2;
+            /// <summary> ADC output 3 </summary>
+        public  UInt16 adc3;
+            /// <summary> ADC output 4 </summary>
+        public  UInt16 adc4;
+            /// <summary> ADC output 5 </summary>
+        public  UInt16 adc5;
+            /// <summary> ADC output 6 </summary>
+        public  UInt16 adc6;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_DIGICAM_CONFIGURE = 154;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=15)]
+    public struct mavlink_digicam_configure_t
+    {
+        /// <summary> Correspondent value to given extra_param </summary>
+        public  Single extra_value;
+            /// <summary> Divisor number //e.g. 1000 means 1/1000 (0 means ignore) </summary>
+        public  UInt16 shutter_speed;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) </summary>
+        public  byte mode;
+            /// <summary> F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) </summary>
+        public  byte aperture;
+            /// <summary> ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) </summary>
+        public  byte iso;
+            /// <summary> Exposure type enumeration from 1 to N (0 means ignore) </summary>
+        public  byte exposure_type;
+            /// <summary> Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once </summary>
+        public  byte command_id;
+            /// <summary> Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) </summary>
+        public  byte engine_cut_off;
+            /// <summary> Extra parameters enumeration (0 means ignore) </summary>
+        public  byte extra_param;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_DIGICAM_CONTROL = 155;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=13)]
+    public struct mavlink_digicam_control_t
+    {
+        /// <summary> Correspondent value to given extra_param </summary>
+        public  Single extra_value;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> 0: stop, 1: start or keep it up //Session control e.g. show/hide lens </summary>
+        public  byte session;
+            /// <summary> 1 to N //Zoom's absolute position (0 means ignore) </summary>
+        public  byte zoom_pos;
+            /// <summary> -100 to 100 //Zooming step value to offset zoom from the current position </summary>
+        public  byte zoom_step;
+            /// <summary> 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus </summary>
+        public  byte focus_lock;
+            /// <summary> 0: ignore, 1: shot or start filming </summary>
+        public  byte shot;
+            /// <summary> Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once </summary>
+        public  byte command_id;
+            /// <summary> Extra parameters enumeration (0 means ignore) </summary>
+        public  byte extra_param;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MOUNT_CONFIGURE = 156;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)]
+    public struct mavlink_mount_configure_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> mount operating mode (see MAV_MOUNT_MODE enum) </summary>
+        public  byte mount_mode;
+            /// <summary> (1 = yes, 0 = no) </summary>
+        public  byte stab_roll;
+            /// <summary> (1 = yes, 0 = no) </summary>
+        public  byte stab_pitch;
+            /// <summary> (1 = yes, 0 = no) </summary>
+        public  byte stab_yaw;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MOUNT_CONTROL = 157;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=15)]
+    public struct mavlink_mount_control_t
+    {
+        /// <summary> pitch(deg*100) or lat, depending on mount mode </summary>
+        public  Int32 input_a;
+            /// <summary> roll(deg*100) or lon depending on mount mode </summary>
+        public  Int32 input_b;
+            /// <summary> yaw(deg*100) or alt (in cm) depending on mount mode </summary>
+        public  Int32 input_c;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) </summary>
+        public  byte save_position;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MOUNT_STATUS = 158;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)]
+    public struct mavlink_mount_status_t
+    {
+        /// <summary> pitch(deg*100) or lat, depending on mount mode </summary>
+        public  Int32 pointing_a;
+            /// <summary> roll(deg*100) or lon depending on mount mode </summary>
+        public  Int32 pointing_b;
+            /// <summary> yaw(deg*100) or alt (in cm) depending on mount mode </summary>
+        public  Int32 pointing_c;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_FENCE_POINT = 160;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)]
+    public struct mavlink_fence_point_t
+    {
+        /// <summary> Latitude of point </summary>
+        public  Single lat;
+            /// <summary> Longitude of point </summary>
+        public  Single lng;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> point index (first point is 1, 0 is for return point) </summary>
+        public  byte idx;
+            /// <summary> total number of points (for sanity checking) </summary>
+        public  byte count;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_FENCE_FETCH_POINT = 161;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)]
+    public struct mavlink_fence_fetch_point_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> point index (first point is 1, 0 is for return point) </summary>
+        public  byte idx;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_FENCE_STATUS = 162;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)]
+    public struct mavlink_fence_status_t
+    {
+        /// <summary> time of last breach in milliseconds since boot </summary>
+        public  UInt32 breach_time;
+            /// <summary> number of fence breaches </summary>
+        public  UInt16 breach_count;
+            /// <summary> 0 if currently inside fence, 1 if outside </summary>
+        public  byte breach_status;
+            /// <summary> last breach type (see FENCE_BREACH_* enum) </summary>
+        public  byte breach_type;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_AHRS = 163;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)]
+    public struct mavlink_ahrs_t
+    {
+        /// <summary> X gyro drift estimate rad/s </summary>
+        public  Single omegaIx;
+            /// <summary> Y gyro drift estimate rad/s </summary>
+        public  Single omegaIy;
+            /// <summary> Z gyro drift estimate rad/s </summary>
+        public  Single omegaIz;
+            /// <summary> average accel_weight </summary>
+        public  Single accel_weight;
+            /// <summary> average renormalisation value </summary>
+        public  Single renorm_val;
+            /// <summary> average error_roll_pitch value </summary>
+        public  Single error_rp;
+            /// <summary> average error_yaw value </summary>
+        public  Single error_yaw;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SIMSTATE = 164;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=36)]
+    public struct mavlink_simstate_t
+    {
+        /// <summary> Roll angle (rad) </summary>
+        public  Single roll;
+            /// <summary> Pitch angle (rad) </summary>
+        public  Single pitch;
+            /// <summary> Yaw angle (rad) </summary>
+        public  Single yaw;
+            /// <summary> X acceleration m/s/s </summary>
+        public  Single xacc;
+            /// <summary> Y acceleration m/s/s </summary>
+        public  Single yacc;
+            /// <summary> Z acceleration m/s/s </summary>
+        public  Single zacc;
+            /// <summary> Angular speed around X axis rad/s </summary>
+        public  Single xgyro;
+            /// <summary> Angular speed around Y axis rad/s </summary>
+        public  Single ygyro;
+            /// <summary> Angular speed around Z axis rad/s </summary>
+        public  Single zgyro;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_HWSTATUS = 165;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)]
+    public struct mavlink_hwstatus_t
+    {
+        /// <summary> board voltage (mV) </summary>
+        public  UInt16 Vcc;
+            /// <summary> I2C error count </summary>
+        public  byte I2Cerr;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_RADIO = 166;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)]
+    public struct mavlink_radio_t
+    {
+        /// <summary> receive errors </summary>
+        public  UInt16 rxerrors;
+            /// <summary> count of error corrected packets </summary>
+        public  UInt16 fixed;
+            /// <summary> local signal strength </summary>
+        public  byte rssi;
+            /// <summary> remote signal strength </summary>
+        public  byte remrssi;
+            /// <summary> how full the tx buffer is as a percentage </summary>
+        public  byte txbuf;
+            /// <summary> background noise level </summary>
+        public  byte noise;
+            /// <summary> remote background noise level </summary>
+        public  byte remnoise;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_HEARTBEAT = 0;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)]
+    public struct mavlink_heartbeat_t
+    {
+        /// <summary> Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. </summary>
+        public  UInt32 custom_mode;
+            /// <summary> Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) </summary>
+        public  byte type;
+            /// <summary> Autopilot type / class. defined in MAV_CLASS ENUM </summary>
+        public  byte autopilot;
+            /// <summary> System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h </summary>
+        public  byte base_mode;
+            /// <summary> System status flag, see MAV_STATUS ENUM </summary>
+        public  byte system_status;
+            /// <summary> MAVLink version </summary>
+        public  byte mavlink_version;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SYS_STATUS = 1;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=31)]
+    public struct mavlink_sys_status_t
+    {
+        /// <summary> Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control </summary>
+        public  UInt32 onboard_control_sensors_present;
+            /// <summary> Bitmask showing which onboard controllers and sensors are enabled:  Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control </summary>
+        public  UInt32 onboard_control_sensors_enabled;
+            /// <summary> Bitmask showing which onboard controllers and sensors are operational or have an error:  Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control </summary>
+        public  UInt32 onboard_control_sensors_health;
+            /// <summary> Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 </summary>
+        public  UInt16 load;
+            /// <summary> Battery voltage, in millivolts (1 = 1 millivolt) </summary>
+        public  UInt16 voltage_battery;
+            /// <summary> Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current </summary>
+        public  Int16 current_battery;
+            /// <summary> Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) </summary>
+        public  UInt16 drop_rate_comm;
+            /// <summary> Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) </summary>
+        public  UInt16 errors_comm;
+            /// <summary> Autopilot-specific errors </summary>
+        public  UInt16 errors_count1;
+            /// <summary> Autopilot-specific errors </summary>
+        public  UInt16 errors_count2;
+            /// <summary> Autopilot-specific errors </summary>
+        public  UInt16 errors_count3;
+            /// <summary> Autopilot-specific errors </summary>
+        public  UInt16 errors_count4;
+            /// <summary> Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery </summary>
+        public  byte battery_remaining;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SYSTEM_TIME = 2;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)]
+    public struct mavlink_system_time_t
+    {
+        /// <summary> Timestamp of the master clock in microseconds since UNIX epoch. </summary>
+        public  UInt64 time_unix_usec;
+            /// <summary> Timestamp of the component clock since boot time in milliseconds. </summary>
+        public  UInt32 time_boot_ms;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_PING = 4;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)]
+    public struct mavlink_ping_t
+    {
+        /// <summary> Unix timestamp in microseconds </summary>
+        public  UInt64 time_usec;
+            /// <summary> PING sequence </summary>
+        public  UInt32 seq;
+            /// <summary> 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 </summary>
+        public  byte target_system;
+            /// <summary> 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 </summary>
+        public  byte target_component;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)]
+    public struct mavlink_change_operator_control_t
+    {
+        /// <summary> System the GCS requests control for </summary>
+        public  byte target_system;
+            /// <summary> 0: request control of this MAV, 1: Release control of this MAV </summary>
+        public  byte control_request;
+            /// <summary> 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. </summary>
+        public  byte version;
+            /// <summary> 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 "!?,.-" </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=25)]
+		public string passkey;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)]
+    public struct mavlink_change_operator_control_ack_t
+    {
+        /// <summary> ID of the GCS this message  </summary>
+        public  byte gcs_system_id;
+            /// <summary> 0: request control of this MAV, 1: Release control of this MAV </summary>
+        public  byte control_request;
+            /// <summary> 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control </summary>
+        public  byte ack;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_AUTH_KEY = 7;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)]
+    public struct mavlink_auth_key_t
+    {
+        /// <summary> key </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)]
+		public string key;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SET_MODE = 11;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)]
+    public struct mavlink_set_mode_t
+    {
+        /// <summary> The new autopilot-specific mode. This field can be ignored by an autopilot. </summary>
+        public  UInt32 custom_mode;
+            /// <summary> The system setting the mode </summary>
+        public  byte target_system;
+            /// <summary> The new base mode </summary>
+        public  byte base_mode;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)]
+    public struct mavlink_param_request_read_t
+    {
+        /// <summary> Parameter index. Send -1 to use the param ID field as identifier </summary>
+        public  Int16 param_index;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> Onboard parameter id </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)]
+		public string param_id;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+    public struct mavlink_param_request_list_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_PARAM_VALUE = 22;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=25)]
+    public struct mavlink_param_value_t
+    {
+        /// <summary> Onboard parameter value </summary>
+        public  Single param_value;
+            /// <summary> Total number of onboard parameters </summary>
+        public  UInt16 param_count;
+            /// <summary> Index of this onboard parameter </summary>
+        public  UInt16 param_index;
+            /// <summary> Onboard parameter id </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)]
+		public string param_id;
+            /// <summary> Onboard parameter type: see MAV_VAR enum </summary>
+        public  byte param_type;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_PARAM_SET = 23;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=23)]
+    public struct mavlink_param_set_t
+    {
+        /// <summary> Onboard parameter value </summary>
+        public  Single param_value;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> Onboard parameter id </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=16)]
+		public string param_id;
+            /// <summary> Onboard parameter type: see MAV_VAR enum </summary>
+        public  byte param_type;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_GPS_RAW_INT = 24;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=30)]
+    public struct mavlink_gps_raw_int_t
+    {
+        /// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt64 time_usec;
+            /// <summary> Latitude in 1E7 degrees </summary>
+        public  Int32 lat;
+            /// <summary> Longitude in 1E7 degrees </summary>
+        public  Int32 lon;
+            /// <summary> Altitude in 1E3 meters (millimeters) above MSL </summary>
+        public  Int32 alt;
+            /// <summary> GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 </summary>
+        public  UInt16 eph;
+            /// <summary> GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 </summary>
+        public  UInt16 epv;
+            /// <summary> GPS ground speed (m/s * 100). If unknown, set to: 65535 </summary>
+        public  UInt16 vel;
+            /// <summary> Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 </summary>
+        public  UInt16 cog;
+            /// <summary> 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. </summary>
+        public  byte fix_type;
+            /// <summary> Number of satellites visible. If unknown, set to 255 </summary>
+        public  byte satellites_visible;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_GPS_STATUS = 25;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=101)]
+    public struct mavlink_gps_status_t
+    {
+        /// <summary> Number of satellites visible </summary>
+        public  byte satellites_visible;
+            /// <summary> Global satellite ID </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)]
+		public byte[] satellite_prn;
+            /// <summary> 0: Satellite not used, 1: used for localization </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)]
+		public byte[] satellite_used;
+            /// <summary> Elevation (0: right on top of receiver, 90: on the horizon) of satellite </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)]
+		public byte[] satellite_elevation;
+            /// <summary> Direction of satellite, 0: 0 deg, 255: 360 deg. </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)]
+		public byte[] satellite_azimuth;
+            /// <summary> Signal to noise ratio of satellite </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)]
+		public byte[] satellite_snr;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SCALED_IMU = 26;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)]
+    public struct mavlink_scaled_imu_t
+    {
+        /// <summary> Timestamp (milliseconds since system boot) </summary>
+        public  UInt32 time_boot_ms;
+            /// <summary> X acceleration (mg) </summary>
+        public  Int16 xacc;
+            /// <summary> Y acceleration (mg) </summary>
+        public  Int16 yacc;
+            /// <summary> Z acceleration (mg) </summary>
+        public  Int16 zacc;
+            /// <summary> Angular speed around X axis (millirad /sec) </summary>
+        public  Int16 xgyro;
+            /// <summary> Angular speed around Y axis (millirad /sec) </summary>
+        public  Int16 ygyro;
+            /// <summary> Angular speed around Z axis (millirad /sec) </summary>
+        public  Int16 zgyro;
+            /// <summary> X Magnetic field (milli tesla) </summary>
+        public  Int16 xmag;
+            /// <summary> Y Magnetic field (milli tesla) </summary>
+        public  Int16 ymag;
+            /// <summary> Z Magnetic field (milli tesla) </summary>
+        public  Int16 zmag;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_RAW_IMU = 27;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=26)]
+    public struct mavlink_raw_imu_t
+    {
+        /// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt64 time_usec;
+            /// <summary> X acceleration (raw) </summary>
+        public  Int16 xacc;
+            /// <summary> Y acceleration (raw) </summary>
+        public  Int16 yacc;
+            /// <summary> Z acceleration (raw) </summary>
+        public  Int16 zacc;
+            /// <summary> Angular speed around X axis (raw) </summary>
+        public  Int16 xgyro;
+            /// <summary> Angular speed around Y axis (raw) </summary>
+        public  Int16 ygyro;
+            /// <summary> Angular speed around Z axis (raw) </summary>
+        public  Int16 zgyro;
+            /// <summary> X Magnetic field (raw) </summary>
+        public  Int16 xmag;
+            /// <summary> Y Magnetic field (raw) </summary>
+        public  Int16 ymag;
+            /// <summary> Z Magnetic field (raw) </summary>
+        public  Int16 zmag;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_RAW_PRESSURE = 28;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)]
+    public struct mavlink_raw_pressure_t
+    {
+        /// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt64 time_usec;
+            /// <summary> Absolute pressure (raw) </summary>
+        public  Int16 press_abs;
+            /// <summary> Differential pressure 1 (raw) </summary>
+        public  Int16 press_diff1;
+            /// <summary> Differential pressure 2 (raw) </summary>
+        public  Int16 press_diff2;
+            /// <summary> Raw Temperature measurement (raw) </summary>
+        public  Int16 temperature;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SCALED_PRESSURE = 29;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)]
+    public struct mavlink_scaled_pressure_t
+    {
+        /// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt32 time_boot_ms;
+            /// <summary> Absolute pressure (hectopascal) </summary>
+        public  Single press_abs;
+            /// <summary> Differential pressure 1 (hectopascal) </summary>
+        public  Single press_diff;
+            /// <summary> Temperature measurement (0.01 degrees celsius) </summary>
+        public  Int16 temperature;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_ATTITUDE = 30;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)]
+    public struct mavlink_attitude_t
+    {
+        /// <summary> Timestamp (milliseconds since system boot) </summary>
+        public  UInt32 time_boot_ms;
+            /// <summary> Roll angle (rad) </summary>
+        public  Single roll;
+            /// <summary> Pitch angle (rad) </summary>
+        public  Single pitch;
+            /// <summary> Yaw angle (rad) </summary>
+        public  Single yaw;
+            /// <summary> Roll angular speed (rad/s) </summary>
+        public  Single rollspeed;
+            /// <summary> Pitch angular speed (rad/s) </summary>
+        public  Single pitchspeed;
+            /// <summary> Yaw angular speed (rad/s) </summary>
+        public  Single yawspeed;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_ATTITUDE_QUATERNION = 31;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)]
+    public struct mavlink_attitude_quaternion_t
+    {
+        /// <summary> Timestamp (milliseconds since system boot) </summary>
+        public  UInt32 time_boot_ms;
+            /// <summary> Quaternion component 1 </summary>
+        public  Single q1;
+            /// <summary> Quaternion component 2 </summary>
+        public  Single q2;
+            /// <summary> Quaternion component 3 </summary>
+        public  Single q3;
+            /// <summary> Quaternion component 4 </summary>
+        public  Single q4;
+            /// <summary> Roll angular speed (rad/s) </summary>
+        public  Single rollspeed;
+            /// <summary> Pitch angular speed (rad/s) </summary>
+        public  Single pitchspeed;
+            /// <summary> Yaw angular speed (rad/s) </summary>
+        public  Single yawspeed;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_LOCAL_POSITION_NED = 32;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)]
+    public struct mavlink_local_position_ned_t
+    {
+        /// <summary> Timestamp (milliseconds since system boot) </summary>
+        public  UInt32 time_boot_ms;
+            /// <summary> X Position </summary>
+        public  Single x;
+            /// <summary> Y Position </summary>
+        public  Single y;
+            /// <summary> Z Position </summary>
+        public  Single z;
+            /// <summary> X Speed </summary>
+        public  Single vx;
+            /// <summary> Y Speed </summary>
+        public  Single vy;
+            /// <summary> Z Speed </summary>
+        public  Single vz;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 33;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)]
+    public struct mavlink_global_position_int_t
+    {
+        /// <summary> Timestamp (milliseconds since system boot) </summary>
+        public  UInt32 time_boot_ms;
+            /// <summary> Latitude, expressed as * 1E7 </summary>
+        public  Int32 lat;
+            /// <summary> Longitude, expressed as * 1E7 </summary>
+        public  Int32 lon;
+            /// <summary> Altitude in meters, expressed as * 1000 (millimeters), above MSL </summary>
+        public  Int32 alt;
+            /// <summary> Altitude above ground in meters, expressed as * 1000 (millimeters) </summary>
+        public  Int32 relative_alt;
+            /// <summary> Ground X Speed (Latitude), expressed as m/s * 100 </summary>
+        public  Int16 vx;
+            /// <summary> Ground Y Speed (Longitude), expressed as m/s * 100 </summary>
+        public  Int16 vy;
+            /// <summary> Ground Z Speed (Altitude), expressed as m/s * 100 </summary>
+        public  Int16 vz;
+            /// <summary> Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 </summary>
+        public  UInt16 hdg;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 34;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)]
+    public struct mavlink_rc_channels_scaled_t
+    {
+        /// <summary> Timestamp (milliseconds since system boot) </summary>
+        public  UInt32 time_boot_ms;
+            /// <summary> RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 </summary>
+        public  Int16 chan1_scaled;
+            /// <summary> RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 </summary>
+        public  Int16 chan2_scaled;
+            /// <summary> RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 </summary>
+        public  Int16 chan3_scaled;
+            /// <summary> RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 </summary>
+        public  Int16 chan4_scaled;
+            /// <summary> RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 </summary>
+        public  Int16 chan5_scaled;
+            /// <summary> RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 </summary>
+        public  Int16 chan6_scaled;
+            /// <summary> RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 </summary>
+        public  Int16 chan7_scaled;
+            /// <summary> RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 </summary>
+        public  Int16 chan8_scaled;
+            /// <summary> Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. </summary>
+        public  byte port;
+            /// <summary> Receive signal strength indicator, 0: 0%, 255: 100% </summary>
+        public  byte rssi;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=22)]
+    public struct mavlink_rc_channels_raw_t
+    {
+        /// <summary> Timestamp (milliseconds since system boot) </summary>
+        public  UInt32 time_boot_ms;
+            /// <summary> RC channel 1 value, in microseconds </summary>
+        public  UInt16 chan1_raw;
+            /// <summary> RC channel 2 value, in microseconds </summary>
+        public  UInt16 chan2_raw;
+            /// <summary> RC channel 3 value, in microseconds </summary>
+        public  UInt16 chan3_raw;
+            /// <summary> RC channel 4 value, in microseconds </summary>
+        public  UInt16 chan4_raw;
+            /// <summary> RC channel 5 value, in microseconds </summary>
+        public  UInt16 chan5_raw;
+            /// <summary> RC channel 6 value, in microseconds </summary>
+        public  UInt16 chan6_raw;
+            /// <summary> RC channel 7 value, in microseconds </summary>
+        public  UInt16 chan7_raw;
+            /// <summary> RC channel 8 value, in microseconds </summary>
+        public  UInt16 chan8_raw;
+            /// <summary> Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. </summary>
+        public  byte port;
+            /// <summary> Receive signal strength indicator, 0: 0%, 255: 100% </summary>
+        public  byte rssi;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 36;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=21)]
+    public struct mavlink_servo_output_raw_t
+    {
+        /// <summary> Timestamp (since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt32 time_usec;
+            /// <summary> Servo output 1 value, in microseconds </summary>
+        public  UInt16 servo1_raw;
+            /// <summary> Servo output 2 value, in microseconds </summary>
+        public  UInt16 servo2_raw;
+            /// <summary> Servo output 3 value, in microseconds </summary>
+        public  UInt16 servo3_raw;
+            /// <summary> Servo output 4 value, in microseconds </summary>
+        public  UInt16 servo4_raw;
+            /// <summary> Servo output 5 value, in microseconds </summary>
+        public  UInt16 servo5_raw;
+            /// <summary> Servo output 6 value, in microseconds </summary>
+        public  UInt16 servo6_raw;
+            /// <summary> Servo output 7 value, in microseconds </summary>
+        public  UInt16 servo7_raw;
+            /// <summary> Servo output 8 value, in microseconds </summary>
+        public  UInt16 servo8_raw;
+            /// <summary> Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. </summary>
+        public  byte port;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST = 37;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)]
+    public struct mavlink_mission_request_partial_list_t
+    {
+        /// <summary> Start index, 0 by default </summary>
+        public  Int16 start_index;
+            /// <summary> End index, -1 by default (-1: send list to end). Else a valid index of the list </summary>
+        public  Int16 end_index;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST = 38;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)]
+    public struct mavlink_mission_write_partial_list_t
+    {
+        /// <summary> Start index, 0 by default and smaller / equal to the largest index of the current onboard list. </summary>
+        public  Int16 start_index;
+            /// <summary> End index, equal or greater than start index. </summary>
+        public  Int16 end_index;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MISSION_ITEM = 39;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)]
+    public struct mavlink_mission_item_t
+    {
+        /// <summary> PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters </summary>
+        public  Single param1;
+            /// <summary> PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds </summary>
+        public  Single param2;
+            /// <summary> PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. </summary>
+        public  Single param3;
+            /// <summary> PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH </summary>
+        public  Single param4;
+            /// <summary> PARAM5 / local: x position, global: latitude </summary>
+        public  Single x;
+            /// <summary> PARAM6 / y position: global: longitude </summary>
+        public  Single y;
+            /// <summary> PARAM7 / z position: global: altitude </summary>
+        public  Single z;
+            /// <summary> Sequence </summary>
+        public  UInt16 seq;
+            /// <summary> The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs </summary>
+        public  UInt16 command;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h </summary>
+        public  byte frame;
+            /// <summary> false:0, true:1 </summary>
+        public  byte current;
+            /// <summary> autocontinue to next wp </summary>
+        public  byte autocontinue;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MISSION_REQUEST = 40;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)]
+    public struct mavlink_mission_request_t
+    {
+        /// <summary> Sequence </summary>
+        public  UInt16 seq;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MISSION_SET_CURRENT = 41;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)]
+    public struct mavlink_mission_set_current_t
+    {
+        /// <summary> Sequence </summary>
+        public  UInt16 seq;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MISSION_CURRENT = 42;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+    public struct mavlink_mission_current_t
+    {
+        /// <summary> Sequence </summary>
+        public  UInt16 seq;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MISSION_REQUEST_LIST = 43;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+    public struct mavlink_mission_request_list_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MISSION_COUNT = 44;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)]
+    public struct mavlink_mission_count_t
+    {
+        /// <summary> Number of mission items in the sequence </summary>
+        public  UInt16 count;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MISSION_CLEAR_ALL = 45;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+    public struct mavlink_mission_clear_all_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MISSION_ITEM_REACHED = 46;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+    public struct mavlink_mission_item_reached_t
+    {
+        /// <summary> Sequence </summary>
+        public  UInt16 seq;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MISSION_ACK = 47;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)]
+    public struct mavlink_mission_ack_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> See MAV_MISSION_RESULT enum </summary>
+        public  byte type;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN = 48;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=13)]
+    public struct mavlink_set_gps_global_origin_t
+    {
+        /// <summary> global position * 1E7 </summary>
+        public  Int32 latitude;
+            /// <summary> global position * 1E7 </summary>
+        public  Int32 longitude;
+            /// <summary> global position * 1000 </summary>
+        public  Int32 altitude;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN = 49;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)]
+    public struct mavlink_gps_global_origin_t
+    {
+        /// <summary> Latitude (WGS84), expressed as * 1E7 </summary>
+        public  Int32 latitude;
+            /// <summary> Longitude (WGS84), expressed as * 1E7 </summary>
+        public  Int32 longitude;
+            /// <summary> Altitude(WGS84), expressed as * 1000 </summary>
+        public  Int32 altitude;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT = 50;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=19)]
+    public struct mavlink_set_local_position_setpoint_t
+    {
+        /// <summary> x position </summary>
+        public  Single x;
+            /// <summary> y position </summary>
+        public  Single y;
+            /// <summary> z position </summary>
+        public  Single z;
+            /// <summary> Desired yaw angle </summary>
+        public  Single yaw;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU </summary>
+        public  byte coordinate_frame;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT = 51;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=17)]
+    public struct mavlink_local_position_setpoint_t
+    {
+        /// <summary> x position </summary>
+        public  Single x;
+            /// <summary> y position </summary>
+        public  Single y;
+            /// <summary> z position </summary>
+        public  Single z;
+            /// <summary> Desired yaw angle </summary>
+        public  Single yaw;
+            /// <summary> Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU </summary>
+        public  byte coordinate_frame;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT = 52;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=15)]
+    public struct mavlink_global_position_setpoint_int_t
+    {
+        /// <summary> WGS84 Latitude position in degrees * 1E7 </summary>
+        public  Int32 latitude;
+            /// <summary> WGS84 Longitude position in degrees * 1E7 </summary>
+        public  Int32 longitude;
+            /// <summary> WGS84 Altitude in meters * 1000 (positive for up) </summary>
+        public  Int32 altitude;
+            /// <summary> Desired yaw angle in degrees * 100 </summary>
+        public  Int16 yaw;
+            /// <summary> Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT </summary>
+        public  byte coordinate_frame;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT = 53;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=15)]
+    public struct mavlink_set_global_position_setpoint_int_t
+    {
+        /// <summary> WGS84 Latitude position in degrees * 1E7 </summary>
+        public  Int32 latitude;
+            /// <summary> WGS84 Longitude position in degrees * 1E7 </summary>
+        public  Int32 longitude;
+            /// <summary> WGS84 Altitude in meters * 1000 (positive for up) </summary>
+        public  Int32 altitude;
+            /// <summary> Desired yaw angle in degrees * 100 </summary>
+        public  Int16 yaw;
+            /// <summary> Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT </summary>
+        public  byte coordinate_frame;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 54;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=27)]
+    public struct mavlink_safety_set_allowed_area_t
+    {
+        /// <summary> x position 1 / Latitude 1 </summary>
+        public  Single p1x;
+            /// <summary> y position 1 / Longitude 1 </summary>
+        public  Single p1y;
+            /// <summary> z position 1 / Altitude 1 </summary>
+        public  Single p1z;
+            /// <summary> x position 2 / Latitude 2 </summary>
+        public  Single p2x;
+            /// <summary> y position 2 / Longitude 2 </summary>
+        public  Single p2y;
+            /// <summary> z position 2 / Altitude 2 </summary>
+        public  Single p2z;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> 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. </summary>
+        public  byte frame;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 55;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=25)]
+    public struct mavlink_safety_allowed_area_t
+    {
+        /// <summary> x position 1 / Latitude 1 </summary>
+        public  Single p1x;
+            /// <summary> y position 1 / Longitude 1 </summary>
+        public  Single p1y;
+            /// <summary> z position 1 / Altitude 1 </summary>
+        public  Single p1z;
+            /// <summary> x position 2 / Latitude 2 </summary>
+        public  Single p2x;
+            /// <summary> y position 2 / Longitude 2 </summary>
+        public  Single p2y;
+            /// <summary> z position 2 / Altitude 2 </summary>
+        public  Single p2z;
+            /// <summary> 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. </summary>
+        public  byte frame;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST = 56;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+    public struct mavlink_set_roll_pitch_yaw_thrust_t
+    {
+        /// <summary> Desired roll angle in radians </summary>
+        public  Single roll;
+            /// <summary> Desired pitch angle in radians </summary>
+        public  Single pitch;
+            /// <summary> Desired yaw angle in radians </summary>
+        public  Single yaw;
+            /// <summary> Collective thrust, normalized to 0 .. 1 </summary>
+        public  Single thrust;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST = 57;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+    public struct mavlink_set_roll_pitch_yaw_speed_thrust_t
+    {
+        /// <summary> Desired roll angular speed in rad/s </summary>
+        public  Single roll_speed;
+            /// <summary> Desired pitch angular speed in rad/s </summary>
+        public  Single pitch_speed;
+            /// <summary> Desired yaw angular speed in rad/s </summary>
+        public  Single yaw_speed;
+            /// <summary> Collective thrust, normalized to 0 .. 1 </summary>
+        public  Single thrust;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT = 58;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)]
+    public struct mavlink_roll_pitch_yaw_thrust_setpoint_t
+    {
+        /// <summary> Timestamp in milliseconds since system boot </summary>
+        public  UInt32 time_boot_ms;
+            /// <summary> Desired roll angle in radians </summary>
+        public  Single roll;
+            /// <summary> Desired pitch angle in radians </summary>
+        public  Single pitch;
+            /// <summary> Desired yaw angle in radians </summary>
+        public  Single yaw;
+            /// <summary> Collective thrust, normalized to 0 .. 1 </summary>
+        public  Single thrust;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT = 59;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)]
+    public struct mavlink_roll_pitch_yaw_speed_thrust_setpoint_t
+    {
+        /// <summary> Timestamp in milliseconds since system boot </summary>
+        public  UInt32 time_boot_ms;
+            /// <summary> Desired roll angular speed in rad/s </summary>
+        public  Single roll_speed;
+            /// <summary> Desired pitch angular speed in rad/s </summary>
+        public  Single pitch_speed;
+            /// <summary> Desired yaw angular speed in rad/s </summary>
+        public  Single yaw_speed;
+            /// <summary> Collective thrust, normalized to 0 .. 1 </summary>
+        public  Single thrust;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=26)]
+    public struct mavlink_nav_controller_output_t
+    {
+        /// <summary> Current desired roll in degrees </summary>
+        public  Single nav_roll;
+            /// <summary> Current desired pitch in degrees </summary>
+        public  Single nav_pitch;
+            /// <summary> Current altitude error in meters </summary>
+        public  Single alt_error;
+            /// <summary> Current airspeed error in meters/second </summary>
+        public  Single aspd_error;
+            /// <summary> Current crosstrack error on x-y plane in meters </summary>
+        public  Single xtrack_error;
+            /// <summary> Current desired heading in degrees </summary>
+        public  Int16 nav_bearing;
+            /// <summary> Bearing to current MISSION/target in degrees </summary>
+        public  Int16 target_bearing;
+            /// <summary> Distance to active MISSION in meters </summary>
+        public  UInt16 wp_dist;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_STATE_CORRECTION = 64;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=36)]
+    public struct mavlink_state_correction_t
+    {
+        /// <summary> x position error </summary>
+        public  Single xErr;
+            /// <summary> y position error </summary>
+        public  Single yErr;
+            /// <summary> z position error </summary>
+        public  Single zErr;
+            /// <summary> roll error (radians) </summary>
+        public  Single rollErr;
+            /// <summary> pitch error (radians) </summary>
+        public  Single pitchErr;
+            /// <summary> yaw error (radians) </summary>
+        public  Single yawErr;
+            /// <summary> x velocity </summary>
+        public  Single vxErr;
+            /// <summary> y velocity </summary>
+        public  Single vyErr;
+            /// <summary> z velocity </summary>
+        public  Single vzErr;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)]
+    public struct mavlink_request_data_stream_t
+    {
+        /// <summary> The requested interval between two messages of this type </summary>
+        public  UInt16 req_message_rate;
+            /// <summary> The target requested to send the message stream. </summary>
+        public  byte target_system;
+            /// <summary> The target requested to send the message stream. </summary>
+        public  byte target_component;
+            /// <summary> The ID of the requested data stream </summary>
+        public  byte req_stream_id;
+            /// <summary> 1 to start sending, 0 to stop sending. </summary>
+        public  byte start_stop;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_DATA_STREAM = 67;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)]
+    public struct mavlink_data_stream_t
+    {
+        /// <summary> The requested interval between two messages of this type </summary>
+        public  UInt16 message_rate;
+            /// <summary> The ID of the requested data stream </summary>
+        public  byte stream_id;
+            /// <summary> 1 stream is enabled, 0 stream is stopped. </summary>
+        public  byte on_off;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MANUAL_CONTROL = 69;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=21)]
+    public struct mavlink_manual_control_t
+    {
+        /// <summary> roll </summary>
+        public  Single roll;
+            /// <summary> pitch </summary>
+        public  Single pitch;
+            /// <summary> yaw </summary>
+        public  Single yaw;
+            /// <summary> thrust </summary>
+        public  Single thrust;
+            /// <summary> The system to be controlled </summary>
+        public  byte target;
+            /// <summary> roll control enabled auto:0, manual:1 </summary>
+        public  byte roll_manual;
+            /// <summary> pitch auto:0, manual:1 </summary>
+        public  byte pitch_manual;
+            /// <summary> yaw auto:0, manual:1 </summary>
+        public  byte yaw_manual;
+            /// <summary> thrust auto:0, manual:1 </summary>
+        public  byte thrust_manual;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+    public struct mavlink_rc_channels_override_t
+    {
+        /// <summary> RC channel 1 value, in microseconds </summary>
+        public  UInt16 chan1_raw;
+            /// <summary> RC channel 2 value, in microseconds </summary>
+        public  UInt16 chan2_raw;
+            /// <summary> RC channel 3 value, in microseconds </summary>
+        public  UInt16 chan3_raw;
+            /// <summary> RC channel 4 value, in microseconds </summary>
+        public  UInt16 chan4_raw;
+            /// <summary> RC channel 5 value, in microseconds </summary>
+        public  UInt16 chan5_raw;
+            /// <summary> RC channel 6 value, in microseconds </summary>
+        public  UInt16 chan6_raw;
+            /// <summary> RC channel 7 value, in microseconds </summary>
+        public  UInt16 chan7_raw;
+            /// <summary> RC channel 8 value, in microseconds </summary>
+        public  UInt16 chan8_raw;
+            /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_VFR_HUD = 74;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)]
+    public struct mavlink_vfr_hud_t
+    {
+        /// <summary> Current airspeed in m/s </summary>
+        public  Single airspeed;
+            /// <summary> Current ground speed in m/s </summary>
+        public  Single groundspeed;
+            /// <summary> Current altitude (MSL), in meters </summary>
+        public  Single alt;
+            /// <summary> Current climb rate in meters/second </summary>
+        public  Single climb;
+            /// <summary> Current heading in degrees, in compass units (0..360, 0=north) </summary>
+        public  Int16 heading;
+            /// <summary> Current throttle setting in integer percent, 0 to 100 </summary>
+        public  UInt16 throttle;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_COMMAND_LONG = 76;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=33)]
+    public struct mavlink_command_long_t
+    {
+        /// <summary> Parameter 1, as defined by MAV_CMD enum. </summary>
+        public  Single param1;
+            /// <summary> Parameter 2, as defined by MAV_CMD enum. </summary>
+        public  Single param2;
+            /// <summary> Parameter 3, as defined by MAV_CMD enum. </summary>
+        public  Single param3;
+            /// <summary> Parameter 4, as defined by MAV_CMD enum. </summary>
+        public  Single param4;
+            /// <summary> Parameter 5, as defined by MAV_CMD enum. </summary>
+        public  Single param5;
+            /// <summary> Parameter 6, as defined by MAV_CMD enum. </summary>
+        public  Single param6;
+            /// <summary> Parameter 7, as defined by MAV_CMD enum. </summary>
+        public  Single param7;
+            /// <summary> Command ID, as defined by MAV_CMD enum. </summary>
+        public  UInt16 command;
+            /// <summary> System which should execute the command </summary>
+        public  byte target_system;
+            /// <summary> Component which should execute the command, 0 for all components </summary>
+        public  byte target_component;
+            /// <summary> 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) </summary>
+        public  byte confirmation;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_COMMAND_ACK = 77;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)]
+    public struct mavlink_command_ack_t
+    {
+        /// <summary> Command ID, as defined by MAV_CMD enum. </summary>
+        public  UInt16 command;
+            /// <summary> See MAV_RESULT enum </summary>
+        public  byte result;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_HIL_STATE = 90;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=56)]
+    public struct mavlink_hil_state_t
+    {
+        /// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt64 time_usec;
+            /// <summary> Roll angle (rad) </summary>
+        public  Single roll;
+            /// <summary> Pitch angle (rad) </summary>
+        public  Single pitch;
+            /// <summary> Yaw angle (rad) </summary>
+        public  Single yaw;
+            /// <summary> Roll angular speed (rad/s) </summary>
+        public  Single rollspeed;
+            /// <summary> Pitch angular speed (rad/s) </summary>
+        public  Single pitchspeed;
+            /// <summary> Yaw angular speed (rad/s) </summary>
+        public  Single yawspeed;
+            /// <summary> Latitude, expressed as * 1E7 </summary>
+        public  Int32 lat;
+            /// <summary> Longitude, expressed as * 1E7 </summary>
+        public  Int32 lon;
+            /// <summary> Altitude in meters, expressed as * 1000 (millimeters) </summary>
+        public  Int32 alt;
+            /// <summary> Ground X Speed (Latitude), expressed as m/s * 100 </summary>
+        public  Int16 vx;
+            /// <summary> Ground Y Speed (Longitude), expressed as m/s * 100 </summary>
+        public  Int16 vy;
+            /// <summary> Ground Z Speed (Altitude), expressed as m/s * 100 </summary>
+        public  Int16 vz;
+            /// <summary> X acceleration (mg) </summary>
+        public  Int16 xacc;
+            /// <summary> Y acceleration (mg) </summary>
+        public  Int16 yacc;
+            /// <summary> Z acceleration (mg) </summary>
+        public  Int16 zacc;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_HIL_CONTROLS = 91;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)]
+    public struct mavlink_hil_controls_t
+    {
+        /// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt64 time_usec;
+            /// <summary> Control output -1 .. 1 </summary>
+        public  Single roll_ailerons;
+            /// <summary> Control output -1 .. 1 </summary>
+        public  Single pitch_elevator;
+            /// <summary> Control output -1 .. 1 </summary>
+        public  Single yaw_rudder;
+            /// <summary> Throttle 0 .. 1 </summary>
+        public  Single throttle;
+            /// <summary> Aux 1, -1 .. 1 </summary>
+        public  Single aux1;
+            /// <summary> Aux 2, -1 .. 1 </summary>
+        public  Single aux2;
+            /// <summary> Aux 3, -1 .. 1 </summary>
+        public  Single aux3;
+            /// <summary> Aux 4, -1 .. 1 </summary>
+        public  Single aux4;
+            /// <summary> System mode (MAV_MODE) </summary>
+        public  byte mode;
+            /// <summary> Navigation mode (MAV_NAV_MODE) </summary>
+        public  byte nav_mode;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW = 92;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=33)]
+    public struct mavlink_hil_rc_inputs_raw_t
+    {
+        /// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt64 time_usec;
+            /// <summary> RC channel 1 value, in microseconds </summary>
+        public  UInt16 chan1_raw;
+            /// <summary> RC channel 2 value, in microseconds </summary>
+        public  UInt16 chan2_raw;
+            /// <summary> RC channel 3 value, in microseconds </summary>
+        public  UInt16 chan3_raw;
+            /// <summary> RC channel 4 value, in microseconds </summary>
+        public  UInt16 chan4_raw;
+            /// <summary> RC channel 5 value, in microseconds </summary>
+        public  UInt16 chan5_raw;
+            /// <summary> RC channel 6 value, in microseconds </summary>
+        public  UInt16 chan6_raw;
+            /// <summary> RC channel 7 value, in microseconds </summary>
+        public  UInt16 chan7_raw;
+            /// <summary> RC channel 8 value, in microseconds </summary>
+        public  UInt16 chan8_raw;
+            /// <summary> RC channel 9 value, in microseconds </summary>
+        public  UInt16 chan9_raw;
+            /// <summary> RC channel 10 value, in microseconds </summary>
+        public  UInt16 chan10_raw;
+            /// <summary> RC channel 11 value, in microseconds </summary>
+        public  UInt16 chan11_raw;
+            /// <summary> RC channel 12 value, in microseconds </summary>
+        public  UInt16 chan12_raw;
+            /// <summary> Receive signal strength indicator, 0: 0%, 255: 100% </summary>
+        public  byte rssi;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_OPTICAL_FLOW = 100;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+    public struct mavlink_optical_flow_t
+    {
+        /// <summary> Timestamp (UNIX) </summary>
+        public  UInt64 time_usec;
+            /// <summary> Ground distance in meters </summary>
+        public  Single ground_distance;
+            /// <summary> Flow in pixels in x-sensor direction </summary>
+        public  Int16 flow_x;
+            /// <summary> Flow in pixels in y-sensor direction </summary>
+        public  Int16 flow_y;
+            /// <summary> Sensor ID </summary>
+        public  byte sensor_id;
+            /// <summary> Optical flow quality / confidence. 0: bad, 255: maximum quality </summary>
+        public  byte quality;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE = 101;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)]
+    public struct mavlink_global_vision_position_estimate_t
+    {
+        /// <summary> Timestamp (milliseconds) </summary>
+        public  UInt64 usec;
+            /// <summary> Global X position </summary>
+        public  Single x;
+            /// <summary> Global Y position </summary>
+        public  Single y;
+            /// <summary> Global Z position </summary>
+        public  Single z;
+            /// <summary> Roll angle in rad </summary>
+        public  Single roll;
+            /// <summary> Pitch angle in rad </summary>
+        public  Single pitch;
+            /// <summary> Yaw angle in rad </summary>
+        public  Single yaw;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE = 102;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)]
+    public struct mavlink_vision_position_estimate_t
+    {
+        /// <summary> Timestamp (milliseconds) </summary>
+        public  UInt64 usec;
+            /// <summary> Global X position </summary>
+        public  Single x;
+            /// <summary> Global Y position </summary>
+        public  Single y;
+            /// <summary> Global Z position </summary>
+        public  Single z;
+            /// <summary> Roll angle in rad </summary>
+        public  Single roll;
+            /// <summary> Pitch angle in rad </summary>
+        public  Single pitch;
+            /// <summary> Yaw angle in rad </summary>
+        public  Single yaw;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE = 103;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)]
+    public struct mavlink_vision_speed_estimate_t
+    {
+        /// <summary> Timestamp (milliseconds) </summary>
+        public  UInt64 usec;
+            /// <summary> Global X speed </summary>
+        public  Single x;
+            /// <summary> Global Y speed </summary>
+        public  Single y;
+            /// <summary> Global Z speed </summary>
+        public  Single z;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE = 104;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)]
+    public struct mavlink_vicon_position_estimate_t
+    {
+        /// <summary> Timestamp (milliseconds) </summary>
+        public  UInt64 usec;
+            /// <summary> Global X position </summary>
+        public  Single x;
+            /// <summary> Global Y position </summary>
+        public  Single y;
+            /// <summary> Global Z position </summary>
+        public  Single z;
+            /// <summary> Roll angle in rad </summary>
+        public  Single roll;
+            /// <summary> Pitch angle in rad </summary>
+        public  Single pitch;
+            /// <summary> Yaw angle in rad </summary>
+        public  Single yaw;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MEMORY_VECT = 249;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=36)]
+    public struct mavlink_memory_vect_t
+    {
+        /// <summary> Starting address of the debug variables </summary>
+        public  UInt16 address;
+            /// <summary> Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below </summary>
+        public  byte ver;
+            /// <summary> Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 </summary>
+        public  byte type;
+            /// <summary> Memory contents at specified address </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)]
+		public byte[] value;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_DEBUG_VECT = 250;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=30)]
+    public struct mavlink_debug_vect_t
+    {
+        /// <summary> Timestamp </summary>
+        public  UInt64 time_usec;
+            /// <summary> x </summary>
+        public  Single x;
+            /// <summary> y </summary>
+        public  Single y;
+            /// <summary> z </summary>
+        public  Single z;
+            /// <summary> Name </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)]
+		public string name;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 251;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+    public struct mavlink_named_value_float_t
+    {
+        /// <summary> Timestamp (milliseconds since system boot) </summary>
+        public  UInt32 time_boot_ms;
+            /// <summary> Floating point value </summary>
+        public  Single value;
+            /// <summary> Name of the debug variable </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)]
+		public string name;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_NAMED_VALUE_INT = 252;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+    public struct mavlink_named_value_int_t
+    {
+        /// <summary> Timestamp (milliseconds since system boot) </summary>
+        public  UInt32 time_boot_ms;
+            /// <summary> Signed integer value </summary>
+        public  Int32 value;
+            /// <summary> Name of the debug variable </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)]
+		public string name;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_STATUSTEXT = 253;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=51)]
+    public struct mavlink_statustext_t
+    {
+        /// <summary> Severity of status, 0 = info message, 255 = critical fault </summary>
+        public  byte severity;
+            /// <summary> Status text message, without null termination character </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=50)]
+		public string text;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_DEBUG = 254;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)]
+    public struct mavlink_debug_t
+    {
+        /// <summary> Timestamp (milliseconds since system boot) </summary>
+        public  UInt32 time_boot_ms;
+            /// <summary> DEBUG value </summary>
+        public  Single value;
+            /// <summary> index of debug variable </summary>
+        public  byte ind;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_EXTENDED_MESSAGE = 255;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)]
+    public struct mavlink_extended_message_t
+    {
+        /// <summary> System which should execute the command </summary>
+        public  byte target_system;
+            /// <summary> Component which should execute the command, 0 for all components </summary>
+        public  byte target_component;
+            /// <summary> Retransmission / ACK flags </summary>
+        public  byte protocol_flags;
+    
+    };
+
+     }
+#endif
+}
diff --git a/Tools/ArdupilotMegaPlanner/MAVLinkTypes0.9.cs b/Tools/ArdupilotMegaPlanner/MAVLinkTypes0.9.cs
index 73d32cf4b850eb7c3a41e6999a900bace7539931..bd6d1276cc8e1fccde6266a2faa1cab91488ce16 100644
--- a/Tools/ArdupilotMegaPlanner/MAVLinkTypes0.9.cs
+++ b/Tools/ArdupilotMegaPlanner/MAVLinkTypes0.9.cs
@@ -5,1348 +5,1832 @@ using System.Runtime.InteropServices;
 
 namespace ArdupilotMega
 {
-    #if !MAVLINK10
+#if !MAVLINK10
     partial class MAVLink
     {
-		public byte[] MAVLINK_MESSAGE_LENGTHS = new byte[] {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, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 5};
-		public byte[] MAVLINK_MESSAGE_CRCS = new byte[] {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 118, 242, 19, 97, 233, 0, 18, 68, 136, 205, 42, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7};
-		public 		enum MAV_MOUNT_MODE
-		{
-			MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization | */
-			MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM. | */
-			MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */
-			MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */
-			MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */
-			MAV_MOUNT_MODE_ENUM_END=5, /*  | */
-		};
-
-		public 		enum MAV_CMD
-		{
-			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|  */
-			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|  */
-			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|  */
-			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|  */
-			RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty|  */
-			LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude|  */
-			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|  */
-			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|  */
-			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|  */
-			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|  */
-			CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty|  */
-			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|  */
-			CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty|  */
-			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|  */
-			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|  */
-			DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty|  */
-			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|  */
-			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|  */
-			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|  */
-			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|  */
-			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|  */
-			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|  */
-			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|  */
-			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|  */
-			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|  */
-			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|  */
-			DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)|  */
-			DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty|  */
-			DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty|  */
-			DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty|  */
-			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|  */
-			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|  */
-			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|  */
-			ENUM_END=246, /*  | */
-		};
-
-		public const byte MAVLINK_MSG_ID_AP_ADC = 153;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_ap_adc_t
-		{
-		 public ushort adc1; /// ADC output 1
-		 public ushort adc2; /// ADC output 2
-		 public ushort adc3; /// ADC output 3
-		 public ushort adc4; /// ADC output 4
-		 public ushort adc5; /// ADC output 5
-		 public ushort adc6; /// ADC output 6
-		};
-
-		public const byte MAVLINK_MSG_ID_AP_ADC_LEN = 12;
-		public const byte MAVLINK_MSG_ID_DCM = 163;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_dcm_t
-		{
-		public float omegaIx; /// X gyro drift estimate rad/s
-		public float omegaIy; /// Y gyro drift estimate rad/s
-		public float omegaIz; /// Z gyro drift estimate rad/s
-		public float accel_weight; /// average accel_weight
-		public float renorm_val; /// average renormalisation value
-		public float error_rp; /// average error_roll_pitch value
-		public float error_yaw; /// average error_yaw value
-		};
-
-		public const byte MAVLINK_MSG_ID_DCM_LEN = 28;
-		public const byte MAVLINK_MSG_ID_DIGICAM_CONFIGURE = 154;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_digicam_configure_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public byte mode; /// Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
-		 public ushort shutter_speed; /// Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
-		 public byte aperture; /// F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
-		 public byte iso; /// ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
-		 public byte exposure_type; /// Exposure type enumeration from 1 to N (0 means ignore)
-		 public byte command_id; /// Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
-		 public byte engine_cut_off; /// Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
-		 public byte extra_param; /// Extra parameters enumeration (0 means ignore)
-		public float extra_value; /// Correspondent value to given extra_param
-		};
-
-		public const byte MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN = 15;
-		public const byte MAVLINK_MSG_ID_DIGICAM_CONTROL = 155;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_digicam_control_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public byte session; /// 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
-		 public byte zoom_pos; /// 1 to N //Zoom's absolute position (0 means ignore)
-		 public byte zoom_step; /// -100 to 100 //Zooming step value to offset zoom from the current position
-		 public byte focus_lock; /// 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
-		 public byte shot; /// 0: ignore, 1: shot or start filming
-		 public byte command_id; /// Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
-		 public byte extra_param; /// Extra parameters enumeration (0 means ignore)
-		public float extra_value; /// Correspondent value to given extra_param
-		};
-
-		public const byte MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN = 13;
-		public const byte MAVLINK_MSG_ID_FENCED_FETCH_POINT = 161;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_fenced_fetch_point_t
-		{
-		 public byte idx; /// point index (first point is 1, 0 is for return point)
-		};
-
-		public const byte MAVLINK_MSG_ID_FENCED_FETCH_POINT_LEN = 1;
-		public const byte MAVLINK_MSG_ID_FENCED_POINT = 160;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_fenced_point_t
-		{
-		 public byte idx; /// point index (first point is 1, 0 is for return point)
-		 public byte count; /// total number of points (for sanity checking)
-		public float lat; /// Latitude of point
-		public float lng; /// Longitude of point
-		};
-
-		public const byte MAVLINK_MSG_ID_FENCED_POINT_LEN = 10;
-		public const byte MAVLINK_MSG_ID_FENCE_FETCH_POINT = 161;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_fence_fetch_point_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public byte idx; /// point index (first point is 1, 0 is for return point)
-		};
-
-		public const byte MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN = 3;
-		public const byte MAVLINK_MSG_ID_FENCE_POINT = 160;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_fence_point_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public byte idx; /// point index (first point is 1, 0 is for return point)
-		 public byte count; /// total number of points (for sanity checking)
-		public float lat; /// Latitude of point
-		public float lng; /// Longitude of point
-		};
-
-		public const byte MAVLINK_MSG_ID_FENCE_POINT_LEN = 12;
-		public const byte MAVLINK_MSG_ID_FENCE_STATUS = 162;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_fence_status_t
-		{
-		 public byte breach_status; /// 0 if currently inside fence, 1 if outside
-		 public ushort breach_count; /// number of fence breaches
-		 public byte breach_type; /// last breach type (see FENCE_BREACH_* enum)
-		 public uint breach_time; /// time of last breach in milliseconds since boot
-		};
-
-		public const byte MAVLINK_MSG_ID_FENCE_STATUS_LEN = 8;
-		public const byte MAVLINK_MSG_ID_HWSTATUS = 165;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_hwstatus_t
-		{
-		 public ushort Vcc; /// board voltage (mV)
-		 public byte I2Cerr; /// I2C error count
-		};
-
-		public const byte MAVLINK_MSG_ID_HWSTATUS_LEN = 3;
-		public const byte MAVLINK_MSG_ID_MEMINFO = 152;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_meminfo_t
-		{
-		 public ushort brkval; /// heap top
-		 public ushort freemem; /// free memory
-		};
-
-		public const byte MAVLINK_MSG_ID_MEMINFO_LEN = 4;
-		public const byte MAVLINK_MSG_ID_MOUNT_CONFIGURE = 156;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_mount_configure_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public byte mount_mode; /// mount operating mode (see MAV_MOUNT_MODE enum)
-		 public byte stab_roll; /// (1 = yes, 0 = no)
-		 public byte stab_pitch; /// (1 = yes, 0 = no)
-		 public byte stab_yaw; /// (1 = yes, 0 = no)
-		};
-
-		public const byte MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN = 6;
-		public const byte MAVLINK_MSG_ID_MOUNT_CONTROL = 157;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_mount_control_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public int input_a; /// pitch(deg*100) or lat, depending on mount mode
-		 public int input_b; /// roll(deg*100) or lon depending on mount mode
-		 public int input_c; /// yaw(deg*100) or alt (in cm) depending on mount mode
-		 public byte save_position; /// if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
-		};
-
-		public const byte MAVLINK_MSG_ID_MOUNT_CONTROL_LEN = 15;
-		public const byte MAVLINK_MSG_ID_MOUNT_STATUS = 158;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_mount_status_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public int pointing_a; /// pitch(deg*100) or lat, depending on mount mode
-		 public int pointing_b; /// roll(deg*100) or lon depending on mount mode
-		 public int pointing_c; /// yaw(deg*100) or alt (in cm) depending on mount mode
-		};
-
-		public const byte MAVLINK_MSG_ID_MOUNT_STATUS_LEN = 14;
-		public const byte MAVLINK_MSG_ID_SENSOR_OFFSETS = 150;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_sensor_offsets_t
-		{
-		 public short mag_ofs_x; /// magnetometer X offset
-		 public short mag_ofs_y; /// magnetometer Y offset
-		 public short mag_ofs_z; /// magnetometer Z offset
-		public float mag_declination; /// magnetic declination (radians)
-		 public int raw_press; /// raw pressure from barometer
-		 public int raw_temp; /// raw temperature from barometer
-		public float gyro_cal_x; /// gyro X calibration
-		public float gyro_cal_y; /// gyro Y calibration
-		public float gyro_cal_z; /// gyro Z calibration
-		public float accel_cal_x; /// accel X calibration
-		public float accel_cal_y; /// accel Y calibration
-		public float accel_cal_z; /// accel Z calibration
-		};
-
-		public const byte MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN = 42;
-		public const byte MAVLINK_MSG_ID_SET_MAG_OFFSETS = 151;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_set_mag_offsets_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public short mag_ofs_x; /// magnetometer X offset
-		 public short mag_ofs_y; /// magnetometer Y offset
-		 public short mag_ofs_z; /// magnetometer Z offset
-		};
-
-		public const byte MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN = 8;
-		public const byte MAVLINK_MSG_ID_SIMSTATE = 164;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_simstate_t
-		{
-		public float roll; /// Roll angle (rad)
-		public float pitch; /// Pitch angle (rad)
-		public float yaw; /// Yaw angle (rad)
-		public float xacc; /// X acceleration m/s/s
-		public float yacc; /// Y acceleration m/s/s
-		public float zacc; /// Z acceleration m/s/s
-		public float xgyro; /// Angular speed around X axis rad/s
-		public float ygyro; /// Angular speed around Y axis rad/s
-		public float zgyro; /// Angular speed around Z axis rad/s
-		};
-
-		public const byte MAVLINK_MSG_ID_SIMSTATE_LEN = 36;
-		public 		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=13, /*  | */
-		};
-
-		public 		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=5, /*  | */
-		};
-
-		public const byte MAVLINK_MSG_ID_ACTION = 10;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_action_t
-		{
-		 public byte target; /// The system executing the action
-		 public byte target_component; /// The component executing the action
-		 public byte action; /// The action id
-		};
-
-		public const byte MAVLINK_MSG_ID_ACTION_LEN = 3;
-		public const byte MAVLINK_MSG_ID_ACTION_ACK = 9;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_action_ack_t
-		{
-		 public byte action; /// The action id
-		 public byte result; /// 0: Action DENIED, 1: Action executed
-		};
-
-		public const byte MAVLINK_MSG_ID_ACTION_ACK_LEN = 2;
-		public const byte MAVLINK_MSG_ID_ATTITUDE = 30;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_attitude_t
-		{
-		 public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
-		public float roll; /// Roll angle (rad)
-		public float pitch; /// Pitch angle (rad)
-		public float yaw; /// Yaw angle (rad)
-		public float rollspeed; /// Roll angular speed (rad/s)
-		public float pitchspeed; /// Pitch angular speed (rad/s)
-		public float yawspeed; /// Yaw angular speed (rad/s)
-		};
-
-		public const byte MAVLINK_MSG_ID_ATTITUDE_LEN = 32;
-		public const byte MAVLINK_MSG_ID_AUTH_KEY = 7;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_auth_key_t
-		{
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=32)] 
-		 public byte[] key; /// key
-		};
-
-		public const byte MAVLINK_MSG_ID_AUTH_KEY_LEN = 32;
-		public const byte MAVLINK_MSG_ID_BOOT = 1;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_boot_t
-		{
-		 public uint version; /// The onboard software version
-		};
-
-		public const byte MAVLINK_MSG_ID_BOOT_LEN = 4;
-		public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_change_operator_control_t
-		{
-		 public byte target_system; /// System the GCS requests control for
-		 public byte control_request; /// 0: request control of this MAV, 1: Release control of this MAV
-		 public byte 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.
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=25)] 
-		 public byte[] 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 "!?,.-"
-		};
-
-		public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN = 28;
-		public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_change_operator_control_ack_t
-		{
-		 public byte gcs_system_id; /// ID of the GCS this message 
-		 public byte control_request; /// 0: request control of this MAV, 1: Release control of this MAV
-		 public byte ack; /// 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
-		};
-
-		public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN = 3;
-		public const byte MAVLINK_MSG_ID_COMMAND = 75;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_command_t
-		{
-		 public byte target_system; /// System which should execute the command
-		 public byte target_component; /// Component which should execute the command, 0 for all components
-		 public byte command; /// Command ID, as defined by MAV_CMD enum.
-		 public byte confirmation; /// 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
-		public float param1; /// Parameter 1, as defined by MAV_CMD enum.
-		public float param2; /// Parameter 2, as defined by MAV_CMD enum.
-		public float param3; /// Parameter 3, as defined by MAV_CMD enum.
-		public float param4; /// Parameter 4, as defined by MAV_CMD enum.
-		};
-
-		public const byte MAVLINK_MSG_ID_COMMAND_LEN = 20;
-		public const byte MAVLINK_MSG_ID_COMMAND_ACK = 76;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_command_ack_t
-		{
-		public float command; /// Current airspeed in m/s
-		public float result; /// 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
-		};
-
-		public const byte MAVLINK_MSG_ID_COMMAND_ACK_LEN = 8;
-		public const byte MAVLINK_MSG_ID_CONTROL_STATUS = 52;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_control_status_t
-		{
-		 public byte position_fix; /// Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix 
-		 public byte vision_fix; /// Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix 
-		 public byte gps_fix; /// GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix 
-		 public byte ahrs_health; /// Attitude estimation health: 0: poor, 255: excellent
-		 public byte control_att; /// 0: Attitude control disabled, 1: enabled
-		 public byte control_pos_xy; /// 0: X, Y position control disabled, 1: enabled
-		 public byte control_pos_z; /// 0: Z position control disabled, 1: enabled
-		 public byte control_pos_yaw; /// 0: Yaw angle control disabled, 1: enabled
-		};
-
-		public const byte MAVLINK_MSG_ID_CONTROL_STATUS_LEN = 8;
-		public const byte MAVLINK_MSG_ID_DEBUG = 255;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_debug_t
-		{
-		 public byte ind; /// index of debug variable
-		public float value; /// DEBUG value
-		};
-
-		public const byte MAVLINK_MSG_ID_DEBUG_LEN = 5;
-		public const byte MAVLINK_MSG_ID_DEBUG_VECT = 251;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_debug_vect_t
-		{
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=10)] 
-		 public byte[] name; /// Name
-		 public ulong usec; /// Timestamp
-		public float x; /// x
-		public float y; /// y
-		public float z; /// z
-		};
-
-		public const byte MAVLINK_MSG_ID_DEBUG_VECT_LEN = 30;
-		public const byte MAVLINK_MSG_ID_GLOBAL_POSITION = 33;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_global_position_t
-		{
-		 public ulong usec; /// Timestamp (microseconds since unix epoch)
-		public float lat; /// Latitude, in degrees
-		public float lon; /// Longitude, in degrees
-		public float alt; /// Absolute altitude, in meters
-		public float vx; /// X Speed (in Latitude direction, positive: going north)
-		public float vy; /// Y Speed (in Longitude direction, positive: going east)
-		public float vz; /// Z Speed (in Altitude direction, positive: going up)
-		};
-
-		public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_LEN = 32;
-		public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 73;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_global_position_int_t
-		{
-		 public int lat; /// Latitude, expressed as * 1E7
-		 public int lon; /// Longitude, expressed as * 1E7
-		 public int alt; /// Altitude in meters, expressed as * 1000 (millimeters)
-		 public short vx; /// Ground X Speed (Latitude), expressed as m/s * 100
-		 public short vy; /// Ground Y Speed (Longitude), expressed as m/s * 100
-		 public short vz; /// Ground Z Speed (Altitude), expressed as m/s * 100
-		};
-
-		public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN = 18;
-		public const byte MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET = 49;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_gps_local_origin_set_t
-		{
-		 public int latitude; /// Latitude (WGS84), expressed as * 1E7
-		 public int longitude; /// Longitude (WGS84), expressed as * 1E7
-		 public int altitude; /// Altitude(WGS84), expressed as * 1000
-		};
-
-		public const byte MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET_LEN = 12;
-		public const byte MAVLINK_MSG_ID_GPS_RAW = 32;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_gps_raw_t
-		{
-		 public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
-		 public byte 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.
-		public float lat; /// Latitude in degrees
-		public float lon; /// Longitude in degrees
-		public float alt; /// Altitude in meters
-		public float eph; /// GPS HDOP
-		public float epv; /// GPS VDOP
-		public float v; /// GPS ground speed
-		public float hdg; /// Compass heading in degrees, 0..360 degrees
-		};
-
-		public const byte MAVLINK_MSG_ID_GPS_RAW_LEN = 37;
-		public const byte MAVLINK_MSG_ID_GPS_RAW_INT = 25;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_gps_raw_int_t
-		{
-		 public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
-		 public byte 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.
-		 public int lat; /// Latitude in 1E7 degrees
-		 public int lon; /// Longitude in 1E7 degrees
-		 public int alt; /// Altitude in 1E3 meters (millimeters)
-		public float eph; /// GPS HDOP
-		public float epv; /// GPS VDOP
-		public float v; /// GPS ground speed (m/s)
-		public float hdg; /// Compass heading in degrees, 0..360 degrees
-		};
-
-		public const byte MAVLINK_MSG_ID_GPS_RAW_INT_LEN = 37;
-		public const byte MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN = 48;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_gps_set_global_origin_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public int latitude; /// global position * 1E7
-		 public int longitude; /// global position * 1E7
-		 public int altitude; /// global position * 1000
-		};
-
-		public const byte MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN_LEN = 14;
-		public const byte MAVLINK_MSG_ID_GPS_STATUS = 27;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_gps_status_t
-		{
-		 public byte satellites_visible; /// Number of satellites visible
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=20)] 
-		 public byte[] satellite_prn; /// Global satellite ID
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=20)] 
-		 public byte[] satellite_used; /// 0: Satellite not used, 1: used for localization
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=20)] 
-		 public byte[] satellite_elevation; /// Elevation (0: right on top of receiver, 90: on the horizon) of satellite
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=20)] 
-		 public byte[] satellite_azimuth; /// Direction of satellite, 0: 0 deg, 255: 360 deg.
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=20)] 
-		 public byte[] satellite_snr; /// Signal to noise ratio of satellite
-		};
-
-		public const byte MAVLINK_MSG_ID_GPS_STATUS_LEN = 101;
-		public const byte MAVLINK_MSG_ID_HEARTBEAT = 0;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_heartbeat_t
-		{
-		 public byte type; /// Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
-		 public byte autopilot; /// Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
-		 public byte mavlink_version; /// MAVLink version
-		};
-
-		public const byte MAVLINK_MSG_ID_HEARTBEAT_LEN = 3;
-		public const byte MAVLINK_MSG_ID_HIL_CONTROLS = 68;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_hil_controls_t
-		{
-		 public ulong time_us; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
-		public float roll_ailerons; /// Control output -3 .. 1
-		public float pitch_elevator; /// Control output -1 .. 1
-		public float yaw_rudder; /// Control output -1 .. 1
-		public float throttle; /// Throttle 0 .. 1
-		 public byte mode; /// System mode (MAV_MODE)
-		 public byte nav_mode; /// Navigation mode (MAV_NAV_MODE)
-		};
-
-		public const byte MAVLINK_MSG_ID_HIL_CONTROLS_LEN = 26;
-		public const byte MAVLINK_MSG_ID_HIL_STATE = 67;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_hil_state_t
-		{
-		 public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
-		public float roll; /// Roll angle (rad)
-		public float pitch; /// Pitch angle (rad)
-		public float yaw; /// Yaw angle (rad)
-		public float rollspeed; /// Roll angular speed (rad/s)
-		public float pitchspeed; /// Pitch angular speed (rad/s)
-		public float yawspeed; /// Yaw angular speed (rad/s)
-		 public int lat; /// Latitude, expressed as * 1E7
-		 public int lon; /// Longitude, expressed as * 1E7
-		 public int alt; /// Altitude in meters, expressed as * 1000 (millimeters)
-		 public short vx; /// Ground X Speed (Latitude), expressed as m/s * 100
-		 public short vy; /// Ground Y Speed (Longitude), expressed as m/s * 100
-		 public short vz; /// Ground Z Speed (Altitude), expressed as m/s * 100
-		 public short xacc; /// X acceleration (mg)
-		 public short yacc; /// Y acceleration (mg)
-		 public short zacc; /// Z acceleration (mg)
-		};
-
-		public const byte MAVLINK_MSG_ID_HIL_STATE_LEN = 56;
-		public const byte MAVLINK_MSG_ID_LOCAL_POSITION = 31;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_local_position_t
-		{
-		 public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
-		public float x; /// X Position
-		public float y; /// Y Position
-		public float z; /// Z Position
-		public float vx; /// X Speed
-		public float vy; /// Y Speed
-		public float vz; /// Z Speed
-		};
-
-		public const byte MAVLINK_MSG_ID_LOCAL_POSITION_LEN = 32;
-		public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT = 51;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_local_position_setpoint_t
-		{
-		public float x; /// x position
-		public float y; /// y position
-		public float z; /// z position
-		public float yaw; /// Desired yaw angle
-		};
-
-		public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN = 16;
-		public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET = 50;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_local_position_setpoint_set_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		public float x; /// x position
-		public float y; /// y position
-		public float z; /// z position
-		public float yaw; /// Desired yaw angle
-		};
-
-		public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET_LEN = 18;
-		public const byte MAVLINK_MSG_ID_MANUAL_CONTROL = 69;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_manual_control_t
-		{
-		 public byte target; /// The system to be controlled
-		public float roll; /// roll
-		public float pitch; /// pitch
-		public float yaw; /// yaw
-		public float thrust; /// thrust
-		 public byte roll_manual; /// roll control enabled auto:0, manual:1
-		 public byte pitch_manual; /// pitch auto:0, manual:1
-		 public byte yaw_manual; /// yaw auto:0, manual:1
-		 public byte thrust_manual; /// thrust auto:0, manual:1
-		};
-
-		public const byte MAVLINK_MSG_ID_MANUAL_CONTROL_LEN = 21;
-		public const byte MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 252;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_named_value_float_t
-		{
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=10)] 
-		 public byte[] name; /// Name of the debug variable
-		public float value; /// Floating point value
-		};
-
-		public const byte MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN = 14;
-		public const byte MAVLINK_MSG_ID_NAMED_VALUE_INT = 253;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_named_value_int_t
-		{
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=10)] 
-		 public byte[] name; /// Name of the debug variable
-		 public int value; /// Signed integer value
-		};
-
-		public const byte MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN = 14;
-		public const byte MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_nav_controller_output_t
-		{
-		public float nav_roll; /// Current desired roll in degrees
-		public float nav_pitch; /// Current desired pitch in degrees
-		 public short nav_bearing; /// Current desired heading in degrees
-		 public short target_bearing; /// Bearing to current waypoint/target in degrees
-		 public ushort wp_dist; /// Distance to active waypoint in meters
-		public float alt_error; /// Current altitude error in meters
-		public float aspd_error; /// Current airspeed error in meters/second
-		public float xtrack_error; /// Current crosstrack error on x-y plane in meters
-		};
-
-		public const byte MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN = 26;
-		public const byte MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT = 140;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_object_detection_event_t
-		{
-		 public uint time; /// Timestamp in milliseconds since system boot
-		 public ushort object_id; /// Object ID
-		 public byte type; /// Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=20)] 
-		 public byte[] name; /// Name of the object as defined by the detector
-		 public byte quality; /// Detection quality / confidence. 0: bad, 255: maximum confidence
-		public float bearing; /// Angle of the object with respect to the body frame in NED coordinates in radians. 0: front
-		public float distance; /// Ground distance in meters
-		};
-
-		public const byte MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT_LEN = 36;
-		public const byte MAVLINK_MSG_ID_OPTICAL_FLOW = 100;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_optical_flow_t
-		{
-		 public ulong time; /// Timestamp (UNIX)
-		 public byte sensor_id; /// Sensor ID
-		 public short flow_x; /// Flow in pixels in x-sensor direction
-		 public short flow_y; /// Flow in pixels in y-sensor direction
-		 public byte quality; /// Optical flow quality / confidence. 0: bad, 255: maximum quality
-		public float ground_distance; /// Ground distance in meters
-		};
-
-		public const byte MAVLINK_MSG_ID_OPTICAL_FLOW_LEN = 18;
-		public const byte MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_param_request_list_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		};
-
-		public const byte MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN = 2;
-		public const byte MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_param_request_read_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=15)] 
-		 public byte[] param_id; /// Onboard parameter id
-		 public short param_index; /// Parameter index. Send -1 to use the param ID field as identifier
-		};
-
-		public const byte MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN = 19;
-		public const byte MAVLINK_MSG_ID_PARAM_SET = 23;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_param_set_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=15)] 
-		 public byte[] param_id; /// Onboard parameter id
-		public float param_value; /// Onboard parameter value
-		};
-
-		public const byte MAVLINK_MSG_ID_PARAM_SET_LEN = 21;
-		public const byte MAVLINK_MSG_ID_PARAM_VALUE = 22;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_param_value_t
-		{
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=15)] 
-		 public byte[] param_id; /// Onboard parameter id
-		public float param_value; /// Onboard parameter value
-		 public ushort param_count; /// Total number of onboard parameters
-		 public ushort param_index; /// Index of this onboard parameter
-		};
-
-		public const byte MAVLINK_MSG_ID_PARAM_VALUE_LEN = 23;
-		public const byte MAVLINK_MSG_ID_PING = 3;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_ping_t
-		{
-		 public uint seq; /// PING sequence
-		 public byte 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
-		 public byte 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
-		 public ulong time; /// Unix timestamp in microseconds
-		};
-
-		public const byte MAVLINK_MSG_ID_PING_LEN = 14;
-		public const byte MAVLINK_MSG_ID_POSITION_TARGET = 63;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_position_target_t
-		{
-		public float x; /// x position
-		public float y; /// y position
-		public float z; /// z position
-		public float yaw; /// yaw orientation in radians, 0 = NORTH
-		};
-
-		public const byte MAVLINK_MSG_ID_POSITION_TARGET_LEN = 16;
-		public const byte MAVLINK_MSG_ID_RAW_IMU = 28;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_raw_imu_t
-		{
-		 public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
-		 public short xacc; /// X acceleration (raw)
-		 public short yacc; /// Y acceleration (raw)
-		 public short zacc; /// Z acceleration (raw)
-		 public short xgyro; /// Angular speed around X axis (raw)
-		 public short ygyro; /// Angular speed around Y axis (raw)
-		 public short zgyro; /// Angular speed around Z axis (raw)
-		 public short xmag; /// X Magnetic field (raw)
-		 public short ymag; /// Y Magnetic field (raw)
-		 public short zmag; /// Z Magnetic field (raw)
-		};
-
-		public const byte MAVLINK_MSG_ID_RAW_IMU_LEN = 26;
-		public const byte MAVLINK_MSG_ID_RAW_PRESSURE = 29;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_raw_pressure_t
-		{
-		 public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
-		 public short press_abs; /// Absolute pressure (raw)
-		 public short press_diff1; /// Differential pressure 1 (raw)
-		 public short press_diff2; /// Differential pressure 2 (raw)
-		 public short temperature; /// Raw Temperature measurement (raw)
-		};
-
-		public const byte MAVLINK_MSG_ID_RAW_PRESSURE_LEN = 16;
-		public const byte MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_rc_channels_override_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public ushort chan1_raw; /// RC channel 1 value, in microseconds
-		 public ushort chan2_raw; /// RC channel 2 value, in microseconds
-		 public ushort chan3_raw; /// RC channel 3 value, in microseconds
-		 public ushort chan4_raw; /// RC channel 4 value, in microseconds
-		 public ushort chan5_raw; /// RC channel 5 value, in microseconds
-		 public ushort chan6_raw; /// RC channel 6 value, in microseconds
-		 public ushort chan7_raw; /// RC channel 7 value, in microseconds
-		 public ushort chan8_raw; /// RC channel 8 value, in microseconds
-		};
-
-		public const byte MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN = 18;
-		public const byte MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_rc_channels_raw_t
-		{
-		 public ushort chan1_raw; /// RC channel 1 value, in microseconds
-		 public ushort chan2_raw; /// RC channel 2 value, in microseconds
-		 public ushort chan3_raw; /// RC channel 3 value, in microseconds
-		 public ushort chan4_raw; /// RC channel 4 value, in microseconds
-		 public ushort chan5_raw; /// RC channel 5 value, in microseconds
-		 public ushort chan6_raw; /// RC channel 6 value, in microseconds
-		 public ushort chan7_raw; /// RC channel 7 value, in microseconds
-		 public ushort chan8_raw; /// RC channel 8 value, in microseconds
-		 public byte rssi; /// Receive signal strength indicator, 0: 0%, 255: 100%
-		};
-
-		public const byte MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN = 17;
-		public const byte MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 36;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_rc_channels_scaled_t
-		{
-		 public short chan1_scaled; /// RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
-		 public short chan2_scaled; /// RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
-		 public short chan3_scaled; /// RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
-		 public short chan4_scaled; /// RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
-		 public short chan5_scaled; /// RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
-		 public short chan6_scaled; /// RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
-		 public short chan7_scaled; /// RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
-		 public short chan8_scaled; /// RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
-		 public byte rssi; /// Receive signal strength indicator, 0: 0%, 255: 100%
-		};
-
-		public const byte MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN = 17;
-		public const byte MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_request_data_stream_t
-		{
-		 public byte target_system; /// The target requested to send the message stream.
-		 public byte target_component; /// The target requested to send the message stream.
-		 public byte req_stream_id; /// The ID of the requested message type
-		 public ushort req_message_rate; /// Update rate in Hertz
-		 public byte start_stop; /// 1 to start sending, 0 to stop sending.
-		};
-
-		public const byte MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN = 6;
-		public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT = 58;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t
-		{
-		 public ulong time_us; /// Timestamp in micro seconds since unix epoch
-		public float roll_speed; /// Desired roll angular speed in rad/s
-		public float pitch_speed; /// Desired pitch angular speed in rad/s
-		public float yaw_speed; /// Desired yaw angular speed in rad/s
-		public float thrust; /// Collective thrust, normalized to 0 .. 1
-		};
-
-		public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN = 24;
-		public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT = 57;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_roll_pitch_yaw_thrust_setpoint_t
-		{
-		 public ulong time_us; /// Timestamp in micro seconds since unix epoch
-		public float roll; /// Desired roll angle in radians
-		public float pitch; /// Desired pitch angle in radians
-		public float yaw; /// Desired yaw angle in radians
-		public float thrust; /// Collective thrust, normalized to 0 .. 1
-		};
-
-		public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN = 24;
-		public const byte MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 54;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_safety_allowed_area_t
-		{
-		 public byte 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.
-		public float p1x; /// x position 1 / Latitude 1
-		public float p1y; /// y position 1 / Longitude 1
-		public float p1z; /// z position 1 / Altitude 1
-		public float p2x; /// x position 2 / Latitude 2
-		public float p2y; /// y position 2 / Longitude 2
-		public float p2z; /// z position 2 / Altitude 2
-		};
-
-		public const byte MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN = 25;
-		public const byte MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 53;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_safety_set_allowed_area_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public byte 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.
-		public float p1x; /// x position 1 / Latitude 1
-		public float p1y; /// y position 1 / Longitude 1
-		public float p1z; /// z position 1 / Altitude 1
-		public float p2x; /// x position 2 / Latitude 2
-		public float p2y; /// y position 2 / Longitude 2
-		public float p2z; /// z position 2 / Altitude 2
-		};
-
-		public const byte MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN = 27;
-		public const byte MAVLINK_MSG_ID_SCALED_IMU = 26;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_scaled_imu_t
-		{
-		 public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
-		 public short xacc; /// X acceleration (mg)
-		 public short yacc; /// Y acceleration (mg)
-		 public short zacc; /// Z acceleration (mg)
-		 public short xgyro; /// Angular speed around X axis (millirad /sec)
-		 public short ygyro; /// Angular speed around Y axis (millirad /sec)
-		 public short zgyro; /// Angular speed around Z axis (millirad /sec)
-		 public short xmag; /// X Magnetic field (milli tesla)
-		 public short ymag; /// Y Magnetic field (milli tesla)
-		 public short zmag; /// Z Magnetic field (milli tesla)
-		};
-
-		public const byte MAVLINK_MSG_ID_SCALED_IMU_LEN = 26;
-		public const byte MAVLINK_MSG_ID_SCALED_PRESSURE = 38;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_scaled_pressure_t
-		{
-		 public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot)
-		public float press_abs; /// Absolute pressure (hectopascal)
-		public float press_diff; /// Differential pressure 1 (hectopascal)
-		 public short temperature; /// Temperature measurement (0.01 degrees celsius)
-		};
-
-		public const byte MAVLINK_MSG_ID_SCALED_PRESSURE_LEN = 18;
-		public const byte MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 37;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_servo_output_raw_t
-		{
-		 public ushort servo1_raw; /// Servo output 1 value, in microseconds
-		 public ushort servo2_raw; /// Servo output 2 value, in microseconds
-		 public ushort servo3_raw; /// Servo output 3 value, in microseconds
-		 public ushort servo4_raw; /// Servo output 4 value, in microseconds
-		 public ushort servo5_raw; /// Servo output 5 value, in microseconds
-		 public ushort servo6_raw; /// Servo output 6 value, in microseconds
-		 public ushort servo7_raw; /// Servo output 7 value, in microseconds
-		 public ushort servo8_raw; /// Servo output 8 value, in microseconds
-		};
-
-		public const byte MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN = 16;
-		public const byte MAVLINK_MSG_ID_SET_ALTITUDE = 65;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_set_altitude_t
-		{
-		 public byte target; /// The system setting the altitude
-		 public uint mode; /// The new altitude in meters
-		};
-
-		public const byte MAVLINK_MSG_ID_SET_ALTITUDE_LEN = 5;
-		public const byte MAVLINK_MSG_ID_SET_MODE = 11;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_set_mode_t
-		{
-		 public byte target; /// The system setting the mode
-		 public byte mode; /// The new mode
-		};
-
-		public const byte MAVLINK_MSG_ID_SET_MODE_LEN = 2;
-		public const byte MAVLINK_MSG_ID_SET_NAV_MODE = 12;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_set_nav_mode_t
-		{
-		 public byte target; /// The system setting the mode
-		 public byte nav_mode; /// The new navigation mode
-		};
-
-		public const byte MAVLINK_MSG_ID_SET_NAV_MODE_LEN = 2;
-		public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST = 56;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_set_roll_pitch_yaw_speed_thrust_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		public float roll_speed; /// Desired roll angular speed in rad/s
-		public float pitch_speed; /// Desired pitch angular speed in rad/s
-		public float yaw_speed; /// Desired yaw angular speed in rad/s
-		public float thrust; /// Collective thrust, normalized to 0 .. 1
-		};
-
-		public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN = 18;
-		public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST = 55;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_set_roll_pitch_yaw_thrust_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		public float roll; /// Desired roll angle in radians
-		public float pitch; /// Desired pitch angle in radians
-		public float yaw; /// Desired yaw angle in radians
-		public float thrust; /// Collective thrust, normalized to 0 .. 1
-		};
-
-		public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN = 18;
-		public const byte MAVLINK_MSG_ID_STATE_CORRECTION = 64;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_state_correction_t
-		{
-		public float xErr; /// x position error
-		public float yErr; /// y position error
-		public float zErr; /// z position error
-		public float rollErr; /// roll error (radians)
-		public float pitchErr; /// pitch error (radians)
-		public float yawErr; /// yaw error (radians)
-		public float vxErr; /// x velocity
-		public float vyErr; /// y velocity
-		public float vzErr; /// z velocity
-		};
-
-		public const byte MAVLINK_MSG_ID_STATE_CORRECTION_LEN = 36;
-		public const byte MAVLINK_MSG_ID_STATUSTEXT = 254;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_statustext_t
-		{
-		 public byte severity; /// Severity of status, 0 = info message, 255 = critical fault
-		[MarshalAs(
-				    	UnmanagedType.ByValArray,
-				    	SizeConst=50)] 
-		 public byte[] text; /// Status text message, without null termination public byteacter
-		};
-
-		public const byte MAVLINK_MSG_ID_STATUSTEXT_LEN = 51;
-		public const byte MAVLINK_MSG_ID_SYSTEM_TIME = 2;
-		public const byte MAVLINK_MSG_ID_SYSTEM_TIME_UTC = 4;
-		public const byte MAVLINK_MSG_ID_SYS_STATUS = 34;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_sys_status_t
-		{
-		 public byte mode; /// System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
-		 public byte nav_mode; /// Navigation mode, see MAV_NAV_MODE ENUM
-		 public byte status; /// System status flag, see MAV_STATUS ENUM
-		 public ushort load; /// Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
-		 public ushort vbat; /// Battery voltage, in millivolts (1 = 1 millivolt)
-		 public ushort battery_remaining; /// Remaining battery energy: (0%: 0, 100%: 1000)
-		 public ushort packet_drop; /// Dropped packets (packets that were corrupted on reception on the MAV)
-		};
-
-		public const byte MAVLINK_MSG_ID_SYS_STATUS_LEN = 11;
-		public const byte MAVLINK_MSG_ID_VFR_HUD = 74;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_vfr_hud_t
-		{
-		public float airspeed; /// Current airspeed in m/s
-		public float groundspeed; /// Current ground speed in m/s
-		 public short heading; /// Current heading in degrees, in compass units (0..360, 0=north)
-		 public ushort throttle; /// Current throttle setting in integer percent, 0 to 100
-		public float alt; /// Current altitude (MSL), in meters
-		public float climb; /// Current climb rate in meters/second
-		};
-
-		public const byte MAVLINK_MSG_ID_VFR_HUD_LEN = 20;
-		public const byte MAVLINK_MSG_ID_WAYPOINT = 39;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_waypoint_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public ushort seq; /// Sequence
-		 public byte frame; /// The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
-		 public byte command; /// The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
-		 public byte current; /// false:0, true:1
-		 public byte autocontinue; /// autocontinue to next wp
-		public float param1; /// PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
-		public float param2; /// PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
-		public 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.
-		public float param4; /// PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
-		public float x; /// PARAM5 / local: x position, global: latitude
-		public float y; /// PARAM6 / y position: global: longitude
-		public float z; /// PARAM7 / z position: global: altitude
-		};
-
-		public const byte MAVLINK_MSG_ID_WAYPOINT_LEN = 36;
-		public const byte MAVLINK_MSG_ID_WAYPOINT_ACK = 47;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_waypoint_ack_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public byte type; /// 0: OK, 1: Error
-		};
-
-		public const byte MAVLINK_MSG_ID_WAYPOINT_ACK_LEN = 3;
-		public const byte MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL = 45;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_waypoint_clear_all_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		};
-
-		public const byte MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL_LEN = 2;
-		public const byte MAVLINK_MSG_ID_WAYPOINT_COUNT = 44;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_waypoint_count_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public ushort count; /// Number of Waypoints in the Sequence
-		};
-
-		public const byte MAVLINK_MSG_ID_WAYPOINT_COUNT_LEN = 4;
-		public const byte MAVLINK_MSG_ID_WAYPOINT_CURRENT = 42;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_waypoint_current_t
-		{
-		 public ushort seq; /// Sequence
-		};
-
-		public const byte MAVLINK_MSG_ID_WAYPOINT_CURRENT_LEN = 2;
-		public const byte MAVLINK_MSG_ID_WAYPOINT_REACHED = 46;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_waypoint_reached_t
-		{
-		 public ushort seq; /// Sequence
-		};
-
-		public const byte MAVLINK_MSG_ID_WAYPOINT_REACHED_LEN = 2;
-		public const byte MAVLINK_MSG_ID_WAYPOINT_REQUEST = 40;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_waypoint_request_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public ushort seq; /// Sequence
-		};
-
-		public const byte MAVLINK_MSG_ID_WAYPOINT_REQUEST_LEN = 4;
-		public const byte MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST = 43;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_waypoint_request_list_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		};
-
-		public const byte MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST_LEN = 2;
-		public const byte MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT = 41;
-		[StructLayout(LayoutKind.Sequential,Pack=1)]
-		public struct __mavlink_waypoint_set_current_t
-		{
-		 public byte target_system; /// System ID
-		 public byte target_component; /// Component ID
-		 public ushort seq; /// Sequence
-		};
-
-		public const byte MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT_LEN = 4;
-		public 		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
-		};
-
-		public 		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
-		};
-
-		public 		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
-		};
-
-		public 		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
-		};
-
-		public 		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
-		};
-
-		public 		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
-		};
-
-		public 		enum MAV_AUTOPILOT_TYPE
-		{
-		    MAV_AUTOPILOT_GENERIC = 0,
-		    MAV_AUTOPILOT_PIXHAWK = 1,
-		    MAV_AUTOPILOT_SLUGS = 2,
-		    MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
-		    MAV_AUTOPILOT_NONE = 4
-		};
-
-		public 		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
-		};
-
-		public 		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
-		};
-
-Type[] mavstructs = new Type[] {typeof( __mavlink_heartbeat_t) ,typeof( __mavlink_boot_t) ,null ,typeof( __mavlink_ping_t) ,null ,typeof( __mavlink_change_operator_control_t) ,typeof( __mavlink_change_operator_control_ack_t) ,typeof( __mavlink_auth_key_t) ,null ,typeof( __mavlink_action_ack_t) ,typeof( __mavlink_action_t) ,typeof( __mavlink_set_mode_t) ,typeof( __mavlink_set_nav_mode_t) ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_param_request_read_t) ,typeof( __mavlink_param_request_list_t) ,typeof( __mavlink_param_value_t) ,typeof( __mavlink_param_set_t) ,null ,typeof( __mavlink_gps_raw_int_t) ,typeof( __mavlink_scaled_imu_t) ,typeof( __mavlink_gps_status_t) ,typeof( __mavlink_raw_imu_t) ,typeof( __mavlink_raw_pressure_t) ,typeof( __mavlink_attitude_t) ,typeof( __mavlink_local_position_t) ,typeof( __mavlink_gps_raw_t) ,typeof( __mavlink_global_position_t) ,typeof( __mavlink_sys_status_t) ,typeof( __mavlink_rc_channels_raw_t) ,typeof( __mavlink_rc_channels_scaled_t) ,typeof( __mavlink_servo_output_raw_t) ,typeof( __mavlink_scaled_pressure_t) ,typeof( __mavlink_waypoint_t) ,typeof( __mavlink_waypoint_request_t) ,typeof( __mavlink_waypoint_set_current_t) ,typeof( __mavlink_waypoint_current_t) ,typeof( __mavlink_waypoint_request_list_t) ,typeof( __mavlink_waypoint_count_t) ,typeof( __mavlink_waypoint_clear_all_t) ,typeof( __mavlink_waypoint_reached_t) ,typeof( __mavlink_waypoint_ack_t) ,typeof( __mavlink_gps_set_global_origin_t) ,typeof( __mavlink_gps_local_origin_set_t) ,typeof( __mavlink_local_position_setpoint_set_t) ,typeof( __mavlink_local_position_setpoint_t) ,typeof( __mavlink_control_status_t) ,typeof( __mavlink_safety_set_allowed_area_t) ,typeof( __mavlink_safety_allowed_area_t) ,typeof( __mavlink_set_roll_pitch_yaw_thrust_t) ,typeof( __mavlink_set_roll_pitch_yaw_speed_thrust_t) ,typeof( __mavlink_roll_pitch_yaw_thrust_setpoint_t) ,typeof( __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t) ,null ,null ,null ,typeof( __mavlink_nav_controller_output_t) ,typeof( __mavlink_position_target_t) ,typeof( __mavlink_state_correction_t) ,typeof( __mavlink_set_altitude_t) ,typeof( __mavlink_request_data_stream_t) ,typeof( __mavlink_hil_state_t) ,typeof( __mavlink_hil_controls_t) ,typeof( __mavlink_manual_control_t) ,typeof( __mavlink_rc_channels_override_t) ,null ,null ,typeof( __mavlink_global_position_int_t) ,typeof( __mavlink_vfr_hud_t) ,typeof( __mavlink_command_t) ,typeof( __mavlink_command_ack_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_optical_flow_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_object_detection_event_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_sensor_offsets_t) ,typeof( __mavlink_set_mag_offsets_t) ,typeof( __mavlink_meminfo_t) ,typeof( __mavlink_ap_adc_t) ,typeof( __mavlink_digicam_configure_t) ,typeof( __mavlink_digicam_control_t) ,typeof( __mavlink_mount_configure_t) ,typeof( __mavlink_mount_control_t) ,typeof( __mavlink_mount_status_t) ,null ,typeof( __mavlink_fence_point_t) ,typeof( __mavlink_fence_fetch_point_t) ,typeof( __mavlink_fence_status_t) ,typeof( __mavlink_dcm_t) ,typeof( __mavlink_simstate_t) ,typeof( __mavlink_hwstatus_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_debug_vect_t) ,typeof( __mavlink_named_value_float_t) ,typeof( __mavlink_named_value_int_t) ,typeof( __mavlink_statustext_t) ,typeof( __mavlink_debug_t) ,null ,};
-
-	}
+        public const string MAVLINK_BUILD_DATE = "Sun Apr  8 12:29:41 2012";
+        public const string MAVLINK_WIRE_PROTOCOL_VERSION = "0.9";
+        public const int MAVLINK_MAX_DIALECT_PAYLOAD_SIZE = 42;
+
+        public const int MAVLINK_LITTLE_ENDIAN = 1;
+        public const int MAVLINK_BIG_ENDIAN = 0;
+
+        public const byte MAVLINK_STX = 85;
+
+        public const byte MAVLINK_ENDIAN = MAVLINK_BIG_ENDIAN;
+
+        public const bool MAVLINK_ALIGNED_FIELDS = (0 == 1);
+
+        public const byte MAVLINK_CRC_EXTRA = 0;
+        
+        public const bool MAVLINK_NEED_BYTE_SWAP = (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN);
+        
+        public byte[] MAVLINK_MESSAGE_LENGTHS = new byte[] {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, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 5};
+
+        public byte[] MAVLINK_MESSAGE_CRCS = new byte[] {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 118, 242, 19, 97, 233, 0, 18, 68, 136, 127, 42, 21, 93, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7};
+
+        public Type[] MAVLINK_MESSAGE_INFO = new Type[] {typeof( mavlink_heartbeat_t ), typeof( mavlink_boot_t ), typeof( mavlink_system_time_t ), typeof( mavlink_ping_t ), typeof( mavlink_system_time_utc_t ), typeof( mavlink_change_operator_control_t ), typeof( mavlink_change_operator_control_ack_t ), typeof( mavlink_auth_key_t ), null, typeof( mavlink_action_ack_t ), typeof( mavlink_action_t ), typeof( mavlink_set_mode_t ), typeof( mavlink_set_nav_mode_t ), null, null, null, null, null, null, null, typeof( mavlink_param_request_read_t ), typeof( mavlink_param_request_list_t ), typeof( mavlink_param_value_t ), typeof( mavlink_param_set_t ), null, typeof( mavlink_gps_raw_int_t ), typeof( mavlink_scaled_imu_t ), typeof( mavlink_gps_status_t ), typeof( mavlink_raw_imu_t ), typeof( mavlink_raw_pressure_t ), typeof( mavlink_attitude_t ), typeof( mavlink_local_position_t ), typeof( mavlink_gps_raw_t ), typeof( mavlink_global_position_t ), typeof( mavlink_sys_status_t ), typeof( mavlink_rc_channels_raw_t ), typeof( mavlink_rc_channels_scaled_t ), typeof( mavlink_servo_output_raw_t ), typeof( mavlink_scaled_pressure_t ), typeof( mavlink_waypoint_t ), typeof( mavlink_waypoint_request_t ), typeof( mavlink_waypoint_set_current_t ), typeof( mavlink_waypoint_current_t ), typeof( mavlink_waypoint_request_list_t ), typeof( mavlink_waypoint_count_t ), typeof( mavlink_waypoint_clear_all_t ), typeof( mavlink_waypoint_reached_t ), typeof( mavlink_waypoint_ack_t ), typeof( mavlink_gps_set_global_origin_t ), typeof( mavlink_gps_local_origin_set_t ), typeof( mavlink_local_position_setpoint_set_t ), typeof( mavlink_local_position_setpoint_t ), typeof( mavlink_control_status_t ), typeof( mavlink_safety_set_allowed_area_t ), typeof( mavlink_safety_allowed_area_t ), typeof( mavlink_set_roll_pitch_yaw_thrust_t ), typeof( mavlink_set_roll_pitch_yaw_speed_thrust_t ), typeof( mavlink_roll_pitch_yaw_thrust_setpoint_t ), typeof( mavlink_roll_pitch_yaw_speed_thrust_setpoint_t ), null, null, null, typeof( mavlink_nav_controller_output_t ), typeof( mavlink_position_target_t ), typeof( mavlink_state_correction_t ), typeof( mavlink_set_altitude_t ), typeof( mavlink_request_data_stream_t ), typeof( mavlink_hil_state_t ), typeof( mavlink_hil_controls_t ), typeof( mavlink_manual_control_t ), typeof( mavlink_rc_channels_override_t ), null, null, typeof( mavlink_global_position_int_t ), typeof( mavlink_vfr_hud_t ), typeof( mavlink_command_t ), typeof( mavlink_command_ack_t ), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_optical_flow_t ), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_object_detection_event_t ), null, null, null, null, null, null, null, null, null, typeof( mavlink_sensor_offsets_t ), typeof( mavlink_set_mag_offsets_t ), typeof( mavlink_meminfo_t ), typeof( mavlink_ap_adc_t ), typeof( mavlink_digicam_configure_t ), typeof( mavlink_digicam_control_t ), typeof( mavlink_mount_configure_t ), typeof( mavlink_mount_control_t ), typeof( mavlink_mount_status_t ), null, typeof( mavlink_fence_point_t ), typeof( mavlink_fence_fetch_point_t ), typeof( mavlink_fence_status_t ), typeof( mavlink_ahrs_t ), typeof( mavlink_simstate_t ), typeof( mavlink_hwstatus_t ), typeof( mavlink_radio_t ), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_debug_vect_t ), typeof( mavlink_named_value_float_t ), typeof( mavlink_named_value_int_t ), typeof( mavlink_statustext_t ), typeof( mavlink_debug_t )};
+
+        public const byte MAVLINK_VERSION = 2;
+    
+        
+        /** @brief Enumeration of possible mount operation modes */
+        public enum MAV_MOUNT_MODE
+        {
+    	///<summary> Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization | </summary>
+            RETRACT=0, 
+        	///<summary> Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM. | </summary>
+            NEUTRAL=1, 
+        	///<summary> Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | </summary>
+            MAVLINK_TARGETING=2, 
+        	///<summary> Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | </summary>
+            RC_TARGETING=3, 
+        	///<summary> Load neutral position and start to point to Lat,Lon,Alt | </summary>
+            GPS_POINT=4, 
+        	///<summary>  | </summary>
+            ENUM_END=5, 
+        
+        };
+        
+        /** @brief  */
+        public enum MAV_CMD
+        {
+    	///<summary> 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|  </summary>
+            WAYPOINT=16, 
+        	///<summary> 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|  </summary>
+            LOITER_UNLIM=17, 
+        	///<summary> 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|  </summary>
+            LOITER_TURNS=18, 
+        	///<summary> 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|  </summary>
+            LOITER_TIME=19, 
+        	///<summary> Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty|  </summary>
+            RETURN_TO_LAUNCH=20, 
+        	///<summary> Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude|  </summary>
+            LAND=21, 
+        	///<summary> 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|  </summary>
+            TAKEOFF=22, 
+        	///<summary> 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|  </summary>
+            ROI=80, 
+        	///<summary> 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|  </summary>
+            PATHPLANNING=81, 
+        	///<summary> 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|  </summary>
+            LAST=95, 
+        	///<summary> Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty|  </summary>
+            CONDITION_DELAY=112, 
+        	///<summary> Ascend/descend at rate.  Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude|  </summary>
+            CONDITION_CHANGE_ALT=113, 
+        	///<summary> Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty|  </summary>
+            CONDITION_DISTANCE=114, 
+        	///<summary> 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|  </summary>
+            CONDITION_YAW=115, 
+        	///<summary> 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|  </summary>
+            CONDITION_LAST=159, 
+        	///<summary> Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty|  </summary>
+            DO_SET_MODE=176, 
+        	///<summary> 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|  </summary>
+            DO_JUMP=177, 
+        	///<summary> 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|  </summary>
+            DO_CHANGE_SPEED=178, 
+        	///<summary> 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|  </summary>
+            DO_SET_HOME=179, 
+        	///<summary> 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|  </summary>
+            DO_SET_PARAMETER=180, 
+        	///<summary> Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty|  </summary>
+            DO_SET_RELAY=181, 
+        	///<summary> 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|  </summary>
+            DO_REPEAT_RELAY=182, 
+        	///<summary> Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty|  </summary>
+            DO_SET_SERVO=183, 
+        	///<summary> 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|  </summary>
+            DO_REPEAT_SERVO=184, 
+        	///<summary> 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|  </summary>
+            DO_CONTROL_VIDEO=200, 
+        	///<summary> 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|  </summary>
+            DO_SET_ROI=201, 
+        	///<summary> Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)|  </summary>
+            DO_DIGICAM_CONFIGURE=202, 
+        	///<summary> Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty|  </summary>
+            DO_DIGICAM_CONTROL=203, 
+        	///<summary> Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty|  </summary>
+            DO_MOUNT_CONFIGURE=204, 
+        	///<summary> Mission command to control a camera or antenna mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty|  </summary>
+            DO_MOUNT_CONTROL=205, 
+        	///<summary> 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|  </summary>
+            DO_LAST=240, 
+        	///<summary> 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|  </summary>
+            PREFLIGHT_CALIBRATION=241, 
+        	///<summary> 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|  </summary>
+            PREFLIGHT_STORAGE=245, 
+        	///<summary>  | </summary>
+            ENUM_END=246, 
+        
+        };
+        
+        /** @brief  */
+        public enum FENCE_ACTION
+        {
+    	///<summary> Disable fenced mode | </summary>
+            NONE=0, 
+        	///<summary> Switched to guided mode to return point (fence point 0) | </summary>
+            GUIDED=1, 
+        	///<summary>  | </summary>
+            ENUM_END=2, 
+        
+        };
+        
+        /** @brief  */
+        public enum FENCE_BREACH
+        {
+    	///<summary> No last fence breach | </summary>
+            NONE=0, 
+        	///<summary> Breached minimum altitude | </summary>
+            MINALT=1, 
+        	///<summary> Breached minimum altitude | </summary>
+            MAXALT=2, 
+        	///<summary> Breached fence boundary | </summary>
+            BOUNDARY=3, 
+        	///<summary>  | </summary>
+            ENUM_END=4, 
+        
+        };
+        
+    
+        
+        /** @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.       */
+        public enum MAV_DATA_STREAM
+        {
+    	///<summary> Enable all data streams | </summary>
+            ALL=0, 
+        	///<summary> Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | </summary>
+            RAW_SENSORS=1, 
+        	///<summary> Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | </summary>
+            EXTENDED_STATUS=2, 
+        	///<summary> Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | </summary>
+            RC_CHANNELS=3, 
+        	///<summary> Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | </summary>
+            RAW_CONTROLLER=4, 
+        	///<summary> Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | </summary>
+            POSITION=6, 
+        	///<summary> Dependent on the autopilot | </summary>
+            EXTRA1=10, 
+        	///<summary> Dependent on the autopilot | </summary>
+            EXTRA2=11, 
+        	///<summary> Dependent on the autopilot | </summary>
+            EXTRA3=12, 
+        	///<summary>  | </summary>
+            ENUM_END=13, 
+        
+        };
+        
+        /** @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).              */
+        public enum MAV_ROI
+        {
+    	///<summary> No region of interest. | </summary>
+            NONE=0, 
+        	///<summary> Point toward next waypoint. | </summary>
+            WPNEXT=1, 
+        	///<summary> Point toward given waypoint. | </summary>
+            WPINDEX=2, 
+        	///<summary> Point toward fixed location. | </summary>
+            LOCATION=3, 
+        	///<summary> Point toward of given id. | </summary>
+            TARGET=4, 
+        	///<summary>  | </summary>
+            ENUM_END=5, 
+        
+        };
+        
+
+    public const byte MAVLINK_MSG_ID_SENSOR_OFFSETS = 150;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=42)]
+    public struct mavlink_sensor_offsets_t
+    {
+        /// <summary> magnetometer X offset </summary>
+        public  Int16 mag_ofs_x;
+            /// <summary> magnetometer Y offset </summary>
+        public  Int16 mag_ofs_y;
+            /// <summary> magnetometer Z offset </summary>
+        public  Int16 mag_ofs_z;
+            /// <summary> magnetic declination (radians) </summary>
+        public  Single mag_declination;
+            /// <summary> raw pressure from barometer </summary>
+        public  Int32 raw_press;
+            /// <summary> raw temperature from barometer </summary>
+        public  Int32 raw_temp;
+            /// <summary> gyro X calibration </summary>
+        public  Single gyro_cal_x;
+            /// <summary> gyro Y calibration </summary>
+        public  Single gyro_cal_y;
+            /// <summary> gyro Z calibration </summary>
+        public  Single gyro_cal_z;
+            /// <summary> accel X calibration </summary>
+        public  Single accel_cal_x;
+            /// <summary> accel Y calibration </summary>
+        public  Single accel_cal_y;
+            /// <summary> accel Z calibration </summary>
+        public  Single accel_cal_z;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SET_MAG_OFFSETS = 151;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)]
+    public struct mavlink_set_mag_offsets_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> magnetometer X offset </summary>
+        public  Int16 mag_ofs_x;
+            /// <summary> magnetometer Y offset </summary>
+        public  Int16 mag_ofs_y;
+            /// <summary> magnetometer Z offset </summary>
+        public  Int16 mag_ofs_z;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MEMINFO = 152;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)]
+    public struct mavlink_meminfo_t
+    {
+        /// <summary> heap top </summary>
+        public  UInt16 brkval;
+            /// <summary> free memory </summary>
+        public  UInt16 freemem;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_AP_ADC = 153;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)]
+    public struct mavlink_ap_adc_t
+    {
+        /// <summary> ADC output 1 </summary>
+        public  UInt16 adc1;
+            /// <summary> ADC output 2 </summary>
+        public  UInt16 adc2;
+            /// <summary> ADC output 3 </summary>
+        public  UInt16 adc3;
+            /// <summary> ADC output 4 </summary>
+        public  UInt16 adc4;
+            /// <summary> ADC output 5 </summary>
+        public  UInt16 adc5;
+            /// <summary> ADC output 6 </summary>
+        public  UInt16 adc6;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_DIGICAM_CONFIGURE = 154;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=15)]
+    public struct mavlink_digicam_configure_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) </summary>
+        public  byte mode;
+            /// <summary> Divisor number //e.g. 1000 means 1/1000 (0 means ignore) </summary>
+        public  UInt16 shutter_speed;
+            /// <summary> F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) </summary>
+        public  byte aperture;
+            /// <summary> ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) </summary>
+        public  byte iso;
+            /// <summary> Exposure type enumeration from 1 to N (0 means ignore) </summary>
+        public  byte exposure_type;
+            /// <summary> Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once </summary>
+        public  byte command_id;
+            /// <summary> Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) </summary>
+        public  byte engine_cut_off;
+            /// <summary> Extra parameters enumeration (0 means ignore) </summary>
+        public  byte extra_param;
+            /// <summary> Correspondent value to given extra_param </summary>
+        public  Single extra_value;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_DIGICAM_CONTROL = 155;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=13)]
+    public struct mavlink_digicam_control_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> 0: stop, 1: start or keep it up //Session control e.g. show/hide lens </summary>
+        public  byte session;
+            /// <summary> 1 to N //Zoom's absolute position (0 means ignore) </summary>
+        public  byte zoom_pos;
+            /// <summary> -100 to 100 //Zooming step value to offset zoom from the current position </summary>
+        public  byte zoom_step;
+            /// <summary> 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus </summary>
+        public  byte focus_lock;
+            /// <summary> 0: ignore, 1: shot or start filming </summary>
+        public  byte shot;
+            /// <summary> Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once </summary>
+        public  byte command_id;
+            /// <summary> Extra parameters enumeration (0 means ignore) </summary>
+        public  byte extra_param;
+            /// <summary> Correspondent value to given extra_param </summary>
+        public  Single extra_value;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MOUNT_CONFIGURE = 156;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)]
+    public struct mavlink_mount_configure_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> mount operating mode (see MAV_MOUNT_MODE enum) </summary>
+        public  byte mount_mode;
+            /// <summary> (1 = yes, 0 = no) </summary>
+        public  byte stab_roll;
+            /// <summary> (1 = yes, 0 = no) </summary>
+        public  byte stab_pitch;
+            /// <summary> (1 = yes, 0 = no) </summary>
+        public  byte stab_yaw;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MOUNT_CONTROL = 157;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=15)]
+    public struct mavlink_mount_control_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> pitch(deg*100) or lat, depending on mount mode </summary>
+        public  Int32 input_a;
+            /// <summary> roll(deg*100) or lon depending on mount mode </summary>
+        public  Int32 input_b;
+            /// <summary> yaw(deg*100) or alt (in cm) depending on mount mode </summary>
+        public  Int32 input_c;
+            /// <summary> if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) </summary>
+        public  byte save_position;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MOUNT_STATUS = 158;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)]
+    public struct mavlink_mount_status_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> pitch(deg*100) or lat, depending on mount mode </summary>
+        public  Int32 pointing_a;
+            /// <summary> roll(deg*100) or lon depending on mount mode </summary>
+        public  Int32 pointing_b;
+            /// <summary> yaw(deg*100) or alt (in cm) depending on mount mode </summary>
+        public  Int32 pointing_c;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_FENCE_POINT = 160;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)]
+    public struct mavlink_fence_point_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> point index (first point is 1, 0 is for return point) </summary>
+        public  byte idx;
+            /// <summary> total number of points (for sanity checking) </summary>
+        public  byte count;
+            /// <summary> Latitude of point </summary>
+        public  Single lat;
+            /// <summary> Longitude of point </summary>
+        public  Single lng;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_FENCE_FETCH_POINT = 161;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)]
+    public struct mavlink_fence_fetch_point_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> point index (first point is 1, 0 is for return point) </summary>
+        public  byte idx;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_FENCE_STATUS = 162;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)]
+    public struct mavlink_fence_status_t
+    {
+        /// <summary> 0 if currently inside fence, 1 if outside </summary>
+        public  byte breach_status;
+            /// <summary> number of fence breaches </summary>
+        public  UInt16 breach_count;
+            /// <summary> last breach type (see FENCE_BREACH_* enum) </summary>
+        public  byte breach_type;
+            /// <summary> time of last breach in milliseconds since boot </summary>
+        public  UInt32 breach_time;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_AHRS = 163;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)]
+    public struct mavlink_ahrs_t
+    {
+        /// <summary> X gyro drift estimate rad/s </summary>
+        public  Single omegaIx;
+            /// <summary> Y gyro drift estimate rad/s </summary>
+        public  Single omegaIy;
+            /// <summary> Z gyro drift estimate rad/s </summary>
+        public  Single omegaIz;
+            /// <summary> average accel_weight </summary>
+        public  Single accel_weight;
+            /// <summary> average renormalisation value </summary>
+        public  Single renorm_val;
+            /// <summary> average error_roll_pitch value </summary>
+        public  Single error_rp;
+            /// <summary> average error_yaw value </summary>
+        public  Single error_yaw;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SIMSTATE = 164;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=36)]
+    public struct mavlink_simstate_t
+    {
+        /// <summary> Roll angle (rad) </summary>
+        public  Single roll;
+            /// <summary> Pitch angle (rad) </summary>
+        public  Single pitch;
+            /// <summary> Yaw angle (rad) </summary>
+        public  Single yaw;
+            /// <summary> X acceleration m/s/s </summary>
+        public  Single xacc;
+            /// <summary> Y acceleration m/s/s </summary>
+        public  Single yacc;
+            /// <summary> Z acceleration m/s/s </summary>
+        public  Single zacc;
+            /// <summary> Angular speed around X axis rad/s </summary>
+        public  Single xgyro;
+            /// <summary> Angular speed around Y axis rad/s </summary>
+        public  Single ygyro;
+            /// <summary> Angular speed around Z axis rad/s </summary>
+        public  Single zgyro;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_HWSTATUS = 165;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)]
+    public struct mavlink_hwstatus_t
+    {
+        /// <summary> board voltage (mV) </summary>
+        public  UInt16 Vcc;
+            /// <summary> I2C error count </summary>
+        public  byte I2Cerr;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_RADIO = 166;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=9)]
+    public struct mavlink_radio_t
+    {
+        /// <summary> local signal strength </summary>
+        public  byte rssi;
+            /// <summary> remote signal strength </summary>
+        public  byte remrssi;
+            /// <summary> how full the tx buffer is as a percentage </summary>
+        public  byte txbuf;
+            /// <summary> background noise level </summary>
+        public  byte noise;
+            /// <summary> remote background noise level </summary>
+        public  byte remnoise;
+            /// <summary> receive errors </summary>
+        public  UInt16 rxerrors;
+            /// <summary> count of error corrected packets </summary>
+        public  UInt16 fixedp;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_HEARTBEAT = 0;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)]
+    public struct mavlink_heartbeat_t
+    {
+        /// <summary> Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) </summary>
+        public  byte type;
+            /// <summary> Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM </summary>
+        public  byte autopilot;
+            /// <summary> MAVLink version </summary>
+        public  byte mavlink_version;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_BOOT = 1;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)]
+    public struct mavlink_boot_t
+    {
+        /// <summary> The onboard software version </summary>
+        public  UInt32 version;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SYSTEM_TIME = 2;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)]
+    public struct mavlink_system_time_t
+    {
+        /// <summary> Timestamp of the master clock in microseconds since UNIX epoch. </summary>
+        public  UInt64 time_usec;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_PING = 3;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)]
+    public struct mavlink_ping_t
+    {
+        /// <summary> PING sequence </summary>
+        public  UInt32 seq;
+            /// <summary> 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 </summary>
+        public  byte target_system;
+            /// <summary> 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 </summary>
+        public  byte target_component;
+            /// <summary> Unix timestamp in microseconds </summary>
+        public  UInt64 time;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SYSTEM_TIME_UTC = 4;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)]
+    public struct mavlink_system_time_utc_t
+    {
+        /// <summary> GPS UTC date ddmmyy </summary>
+        public  UInt32 utc_date;
+            /// <summary> GPS UTC time hhmmss </summary>
+        public  UInt32 utc_time;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=28)]
+    public struct mavlink_change_operator_control_t
+    {
+        /// <summary> System the GCS requests control for </summary>
+        public  byte target_system;
+            /// <summary> 0: request control of this MAV, 1: Release control of this MAV </summary>
+        public  byte control_request;
+            /// <summary> 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. </summary>
+        public  byte version;
+            /// <summary> 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 "!?,.-" </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=25)]
+		public string passkey;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)]
+    public struct mavlink_change_operator_control_ack_t
+    {
+        /// <summary> ID of the GCS this message  </summary>
+        public  byte gcs_system_id;
+            /// <summary> 0: request control of this MAV, 1: Release control of this MAV </summary>
+        public  byte control_request;
+            /// <summary> 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control </summary>
+        public  byte ack;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_AUTH_KEY = 7;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)]
+    public struct mavlink_auth_key_t
+    {
+        /// <summary> key </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=32)]
+		public string key;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_ACTION_ACK = 9;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+    public struct mavlink_action_ack_t
+    {
+        /// <summary> The action id </summary>
+        public  byte action;
+            /// <summary> 0: Action DENIED, 1: Action executed </summary>
+        public  byte result;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_ACTION = 10;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)]
+    public struct mavlink_action_t
+    {
+        /// <summary> The system executing the action </summary>
+        public  byte target;
+            /// <summary> The component executing the action </summary>
+        public  byte target_component;
+            /// <summary> The action id </summary>
+        public  byte action;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SET_MODE = 11;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+    public struct mavlink_set_mode_t
+    {
+        /// <summary> The system setting the mode </summary>
+        public  byte target;
+            /// <summary> The new mode </summary>
+        public  byte mode;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SET_NAV_MODE = 12;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+    public struct mavlink_set_nav_mode_t
+    {
+        /// <summary> The system setting the mode </summary>
+        public  byte target;
+            /// <summary> The new navigation mode </summary>
+        public  byte nav_mode;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=19)]
+    public struct mavlink_param_request_read_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> Onboard parameter id </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=15)]
+		public byte[] param_id;
+            /// <summary> Parameter index. Send -1 to use the param ID field as identifier </summary>
+        public  Int16 param_index;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+    public struct mavlink_param_request_list_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_PARAM_VALUE = 22;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=23)]
+    public struct mavlink_param_value_t
+    {
+        /// <summary> Onboard parameter id </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=15)]
+		public byte[] param_id;
+            /// <summary> Onboard parameter value </summary>
+        public  Single param_value;
+            /// <summary> Total number of onboard parameters </summary>
+        public  UInt16 param_count;
+            /// <summary> Index of this onboard parameter </summary>
+        public  UInt16 param_index;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_PARAM_SET = 23;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=21)]
+    public struct mavlink_param_set_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> Onboard parameter id </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=15)]
+		public byte[] param_id;
+            /// <summary> Onboard parameter value </summary>
+        public  Single param_value;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_GPS_RAW_INT = 25;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)]
+    public struct mavlink_gps_raw_int_t
+    {
+        /// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt64 usec;
+            /// <summary> 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. </summary>
+        public  byte fix_type;
+            /// <summary> Latitude in 1E7 degrees </summary>
+        public  Int32 lat;
+            /// <summary> Longitude in 1E7 degrees </summary>
+        public  Int32 lon;
+            /// <summary> Altitude in 1E3 meters (millimeters) </summary>
+        public  Int32 alt;
+            /// <summary> GPS HDOP </summary>
+        public  Single eph;
+            /// <summary> GPS VDOP </summary>
+        public  Single epv;
+            /// <summary> GPS ground speed (m/s) </summary>
+        public  Single v;
+            /// <summary> Compass heading in degrees, 0..360 degrees </summary>
+        public  Single hdg;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SCALED_IMU = 26;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=26)]
+    public struct mavlink_scaled_imu_t
+    {
+        /// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt64 usec;
+            /// <summary> X acceleration (mg) </summary>
+        public  Int16 xacc;
+            /// <summary> Y acceleration (mg) </summary>
+        public  Int16 yacc;
+            /// <summary> Z acceleration (mg) </summary>
+        public  Int16 zacc;
+            /// <summary> Angular speed around X axis (millirad /sec) </summary>
+        public  Int16 xgyro;
+            /// <summary> Angular speed around Y axis (millirad /sec) </summary>
+        public  Int16 ygyro;
+            /// <summary> Angular speed around Z axis (millirad /sec) </summary>
+        public  Int16 zgyro;
+            /// <summary> X Magnetic field (milli tesla) </summary>
+        public  Int16 xmag;
+            /// <summary> Y Magnetic field (milli tesla) </summary>
+        public  Int16 ymag;
+            /// <summary> Z Magnetic field (milli tesla) </summary>
+        public  Int16 zmag;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_GPS_STATUS = 27;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=101)]
+    public struct mavlink_gps_status_t
+    {
+        /// <summary> Number of satellites visible </summary>
+        public  byte satellites_visible;
+            /// <summary> Global satellite ID </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)]
+		public byte[] satellite_prn;
+            /// <summary> 0: Satellite not used, 1: used for localization </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)]
+		public byte[] satellite_used;
+            /// <summary> Elevation (0: right on top of receiver, 90: on the horizon) of satellite </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)]
+		public byte[] satellite_elevation;
+            /// <summary> Direction of satellite, 0: 0 deg, 255: 360 deg. </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)]
+		public byte[] satellite_azimuth;
+            /// <summary> Signal to noise ratio of satellite </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)]
+		public byte[] satellite_snr;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_RAW_IMU = 28;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=26)]
+    public struct mavlink_raw_imu_t
+    {
+        /// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt64 usec;
+            /// <summary> X acceleration (raw) </summary>
+        public  Int16 xacc;
+            /// <summary> Y acceleration (raw) </summary>
+        public  Int16 yacc;
+            /// <summary> Z acceleration (raw) </summary>
+        public  Int16 zacc;
+            /// <summary> Angular speed around X axis (raw) </summary>
+        public  Int16 xgyro;
+            /// <summary> Angular speed around Y axis (raw) </summary>
+        public  Int16 ygyro;
+            /// <summary> Angular speed around Z axis (raw) </summary>
+        public  Int16 zgyro;
+            /// <summary> X Magnetic field (raw) </summary>
+        public  Int16 xmag;
+            /// <summary> Y Magnetic field (raw) </summary>
+        public  Int16 ymag;
+            /// <summary> Z Magnetic field (raw) </summary>
+        public  Int16 zmag;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_RAW_PRESSURE = 29;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)]
+    public struct mavlink_raw_pressure_t
+    {
+        /// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt64 usec;
+            /// <summary> Absolute pressure (raw) </summary>
+        public  Int16 press_abs;
+            /// <summary> Differential pressure 1 (raw) </summary>
+        public  Int16 press_diff1;
+            /// <summary> Differential pressure 2 (raw) </summary>
+        public  Int16 press_diff2;
+            /// <summary> Raw Temperature measurement (raw) </summary>
+        public  Int16 temperature;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SCALED_PRESSURE = 38;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+    public struct mavlink_scaled_pressure_t
+    {
+        /// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt64 usec;
+            /// <summary> Absolute pressure (hectopascal) </summary>
+        public  Single press_abs;
+            /// <summary> Differential pressure 1 (hectopascal) </summary>
+        public  Single press_diff;
+            /// <summary> Temperature measurement (0.01 degrees celsius) </summary>
+        public  Int16 temperature;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_ATTITUDE = 30;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)]
+    public struct mavlink_attitude_t
+    {
+        /// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt64 usec;
+            /// <summary> Roll angle (rad) </summary>
+        public  Single roll;
+            /// <summary> Pitch angle (rad) </summary>
+        public  Single pitch;
+            /// <summary> Yaw angle (rad) </summary>
+        public  Single yaw;
+            /// <summary> Roll angular speed (rad/s) </summary>
+        public  Single rollspeed;
+            /// <summary> Pitch angular speed (rad/s) </summary>
+        public  Single pitchspeed;
+            /// <summary> Yaw angular speed (rad/s) </summary>
+        public  Single yawspeed;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_LOCAL_POSITION = 31;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)]
+    public struct mavlink_local_position_t
+    {
+        /// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt64 usec;
+            /// <summary> X Position </summary>
+        public  Single x;
+            /// <summary> Y Position </summary>
+        public  Single y;
+            /// <summary> Z Position </summary>
+        public  Single z;
+            /// <summary> X Speed </summary>
+        public  Single vx;
+            /// <summary> Y Speed </summary>
+        public  Single vy;
+            /// <summary> Z Speed </summary>
+        public  Single vz;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_GLOBAL_POSITION = 33;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=32)]
+    public struct mavlink_global_position_t
+    {
+        /// <summary> Timestamp (microseconds since unix epoch) </summary>
+        public  UInt64 usec;
+            /// <summary> Latitude, in degrees </summary>
+        public  Single lat;
+            /// <summary> Longitude, in degrees </summary>
+        public  Single lon;
+            /// <summary> Absolute altitude, in meters </summary>
+        public  Single alt;
+            /// <summary> X Speed (in Latitude direction, positive: going north) </summary>
+        public  Single vx;
+            /// <summary> Y Speed (in Longitude direction, positive: going east) </summary>
+        public  Single vy;
+            /// <summary> Z Speed (in Altitude direction, positive: going up) </summary>
+        public  Single vz;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_GPS_RAW = 32;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=37)]
+    public struct mavlink_gps_raw_t
+    {
+        /// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt64 usec;
+            /// <summary> 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. </summary>
+        public  byte fix_type;
+            /// <summary> Latitude in degrees </summary>
+        public  Single lat;
+            /// <summary> Longitude in degrees </summary>
+        public  Single lon;
+            /// <summary> Altitude in meters </summary>
+        public  Single alt;
+            /// <summary> GPS HDOP </summary>
+        public  Single eph;
+            /// <summary> GPS VDOP </summary>
+        public  Single epv;
+            /// <summary> GPS ground speed </summary>
+        public  Single v;
+            /// <summary> Compass heading in degrees, 0..360 degrees </summary>
+        public  Single hdg;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SYS_STATUS = 34;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=11)]
+    public struct mavlink_sys_status_t
+    {
+        /// <summary> System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h </summary>
+        public  byte mode;
+            /// <summary> Navigation mode, see MAV_NAV_MODE ENUM </summary>
+        public  byte nav_mode;
+            /// <summary> System status flag, see MAV_STATUS ENUM </summary>
+        public  byte status;
+            /// <summary> Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 </summary>
+        public  UInt16 load;
+            /// <summary> Battery voltage, in millivolts (1 = 1 millivolt) </summary>
+        public  UInt16 vbat;
+            /// <summary> Remaining battery energy: (0%: 0, 100%: 1000) </summary>
+        public  UInt16 battery_remaining;
+            /// <summary> Dropped packets (packets that were corrupted on reception on the MAV) </summary>
+        public  UInt16 packet_drop;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=17)]
+    public struct mavlink_rc_channels_raw_t
+    {
+        /// <summary> RC channel 1 value, in microseconds </summary>
+        public  UInt16 chan1_raw;
+            /// <summary> RC channel 2 value, in microseconds </summary>
+        public  UInt16 chan2_raw;
+            /// <summary> RC channel 3 value, in microseconds </summary>
+        public  UInt16 chan3_raw;
+            /// <summary> RC channel 4 value, in microseconds </summary>
+        public  UInt16 chan4_raw;
+            /// <summary> RC channel 5 value, in microseconds </summary>
+        public  UInt16 chan5_raw;
+            /// <summary> RC channel 6 value, in microseconds </summary>
+        public  UInt16 chan6_raw;
+            /// <summary> RC channel 7 value, in microseconds </summary>
+        public  UInt16 chan7_raw;
+            /// <summary> RC channel 8 value, in microseconds </summary>
+        public  UInt16 chan8_raw;
+            /// <summary> Receive signal strength indicator, 0: 0%, 255: 100% </summary>
+        public  byte rssi;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 36;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=17)]
+    public struct mavlink_rc_channels_scaled_t
+    {
+        /// <summary> RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 </summary>
+        public  Int16 chan1_scaled;
+            /// <summary> RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 </summary>
+        public  Int16 chan2_scaled;
+            /// <summary> RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 </summary>
+        public  Int16 chan3_scaled;
+            /// <summary> RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 </summary>
+        public  Int16 chan4_scaled;
+            /// <summary> RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 </summary>
+        public  Int16 chan5_scaled;
+            /// <summary> RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 </summary>
+        public  Int16 chan6_scaled;
+            /// <summary> RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 </summary>
+        public  Int16 chan7_scaled;
+            /// <summary> RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 </summary>
+        public  Int16 chan8_scaled;
+            /// <summary> Receive signal strength indicator, 0: 0%, 255: 100% </summary>
+        public  byte rssi;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 37;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)]
+    public struct mavlink_servo_output_raw_t
+    {
+        /// <summary> Servo output 1 value, in microseconds </summary>
+        public  UInt16 servo1_raw;
+            /// <summary> Servo output 2 value, in microseconds </summary>
+        public  UInt16 servo2_raw;
+            /// <summary> Servo output 3 value, in microseconds </summary>
+        public  UInt16 servo3_raw;
+            /// <summary> Servo output 4 value, in microseconds </summary>
+        public  UInt16 servo4_raw;
+            /// <summary> Servo output 5 value, in microseconds </summary>
+        public  UInt16 servo5_raw;
+            /// <summary> Servo output 6 value, in microseconds </summary>
+        public  UInt16 servo6_raw;
+            /// <summary> Servo output 7 value, in microseconds </summary>
+        public  UInt16 servo7_raw;
+            /// <summary> Servo output 8 value, in microseconds </summary>
+        public  UInt16 servo8_raw;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_WAYPOINT = 39;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=36)]
+    public struct mavlink_waypoint_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> Sequence </summary>
+        public  UInt16 seq;
+            /// <summary> The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h </summary>
+        public  byte frame;
+            /// <summary> The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs </summary>
+        public  byte command;
+            /// <summary> false:0, true:1 </summary>
+        public  byte current;
+            /// <summary> autocontinue to next wp </summary>
+        public  byte autocontinue;
+            /// <summary> PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters </summary>
+        public  Single param1;
+            /// <summary> PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds </summary>
+        public  Single param2;
+            /// <summary> 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. </summary>
+        public  Single param3;
+            /// <summary> PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH </summary>
+        public  Single param4;
+            /// <summary> PARAM5 / local: x position, global: latitude </summary>
+        public  Single x;
+            /// <summary> PARAM6 / y position: global: longitude </summary>
+        public  Single y;
+            /// <summary> PARAM7 / z position: global: altitude </summary>
+        public  Single z;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_WAYPOINT_REQUEST = 40;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)]
+    public struct mavlink_waypoint_request_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> Sequence </summary>
+        public  UInt16 seq;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT = 41;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)]
+    public struct mavlink_waypoint_set_current_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> Sequence </summary>
+        public  UInt16 seq;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_WAYPOINT_CURRENT = 42;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+    public struct mavlink_waypoint_current_t
+    {
+        /// <summary> Sequence </summary>
+        public  UInt16 seq;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST = 43;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+    public struct mavlink_waypoint_request_list_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_WAYPOINT_COUNT = 44;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=4)]
+    public struct mavlink_waypoint_count_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> Number of Waypoints in the Sequence </summary>
+        public  UInt16 count;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL = 45;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+    public struct mavlink_waypoint_clear_all_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_WAYPOINT_REACHED = 46;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=2)]
+    public struct mavlink_waypoint_reached_t
+    {
+        /// <summary> Sequence </summary>
+        public  UInt16 seq;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_WAYPOINT_ACK = 47;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=3)]
+    public struct mavlink_waypoint_ack_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> 0: OK, 1: Error </summary>
+        public  byte type;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN = 48;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)]
+    public struct mavlink_gps_set_global_origin_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> global position * 1E7 </summary>
+        public  Int32 latitude;
+            /// <summary> global position * 1E7 </summary>
+        public  Int32 longitude;
+            /// <summary> global position * 1000 </summary>
+        public  Int32 altitude;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET = 49;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=12)]
+    public struct mavlink_gps_local_origin_set_t
+    {
+        /// <summary> Latitude (WGS84), expressed as * 1E7 </summary>
+        public  Int32 latitude;
+            /// <summary> Longitude (WGS84), expressed as * 1E7 </summary>
+        public  Int32 longitude;
+            /// <summary> Altitude(WGS84), expressed as * 1000 </summary>
+        public  Int32 altitude;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET = 50;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+    public struct mavlink_local_position_setpoint_set_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> x position </summary>
+        public  Single x;
+            /// <summary> y position </summary>
+        public  Single y;
+            /// <summary> z position </summary>
+        public  Single z;
+            /// <summary> Desired yaw angle </summary>
+        public  Single yaw;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT = 51;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)]
+    public struct mavlink_local_position_setpoint_t
+    {
+        /// <summary> x position </summary>
+        public  Single x;
+            /// <summary> y position </summary>
+        public  Single y;
+            /// <summary> z position </summary>
+        public  Single z;
+            /// <summary> Desired yaw angle </summary>
+        public  Single yaw;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_CONTROL_STATUS = 52;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)]
+    public struct mavlink_control_status_t
+    {
+        /// <summary> Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix  </summary>
+        public  byte position_fix;
+            /// <summary> Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix  </summary>
+        public  byte vision_fix;
+            /// <summary> GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix  </summary>
+        public  byte gps_fix;
+            /// <summary> Attitude estimation health: 0: poor, 255: excellent </summary>
+        public  byte ahrs_health;
+            /// <summary> 0: Attitude control disabled, 1: enabled </summary>
+        public  byte control_att;
+            /// <summary> 0: X, Y position control disabled, 1: enabled </summary>
+        public  byte control_pos_xy;
+            /// <summary> 0: Z position control disabled, 1: enabled </summary>
+        public  byte control_pos_z;
+            /// <summary> 0: Yaw angle control disabled, 1: enabled </summary>
+        public  byte control_pos_yaw;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 53;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=27)]
+    public struct mavlink_safety_set_allowed_area_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> 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. </summary>
+        public  byte frame;
+            /// <summary> x position 1 / Latitude 1 </summary>
+        public  Single p1x;
+            /// <summary> y position 1 / Longitude 1 </summary>
+        public  Single p1y;
+            /// <summary> z position 1 / Altitude 1 </summary>
+        public  Single p1z;
+            /// <summary> x position 2 / Latitude 2 </summary>
+        public  Single p2x;
+            /// <summary> y position 2 / Longitude 2 </summary>
+        public  Single p2y;
+            /// <summary> z position 2 / Altitude 2 </summary>
+        public  Single p2z;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 54;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=25)]
+    public struct mavlink_safety_allowed_area_t
+    {
+        /// <summary> 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. </summary>
+        public  byte frame;
+            /// <summary> x position 1 / Latitude 1 </summary>
+        public  Single p1x;
+            /// <summary> y position 1 / Longitude 1 </summary>
+        public  Single p1y;
+            /// <summary> z position 1 / Altitude 1 </summary>
+        public  Single p1z;
+            /// <summary> x position 2 / Latitude 2 </summary>
+        public  Single p2x;
+            /// <summary> y position 2 / Longitude 2 </summary>
+        public  Single p2y;
+            /// <summary> z position 2 / Altitude 2 </summary>
+        public  Single p2z;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST = 55;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+    public struct mavlink_set_roll_pitch_yaw_thrust_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> Desired roll angle in radians </summary>
+        public  Single roll;
+            /// <summary> Desired pitch angle in radians </summary>
+        public  Single pitch;
+            /// <summary> Desired yaw angle in radians </summary>
+        public  Single yaw;
+            /// <summary> Collective thrust, normalized to 0 .. 1 </summary>
+        public  Single thrust;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST = 56;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+    public struct mavlink_set_roll_pitch_yaw_speed_thrust_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> Desired roll angular speed in rad/s </summary>
+        public  Single roll_speed;
+            /// <summary> Desired pitch angular speed in rad/s </summary>
+        public  Single pitch_speed;
+            /// <summary> Desired yaw angular speed in rad/s </summary>
+        public  Single yaw_speed;
+            /// <summary> Collective thrust, normalized to 0 .. 1 </summary>
+        public  Single thrust;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT = 57;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)]
+    public struct mavlink_roll_pitch_yaw_thrust_setpoint_t
+    {
+        /// <summary> Timestamp in micro seconds since unix epoch </summary>
+        public  UInt64 time_us;
+            /// <summary> Desired roll angle in radians </summary>
+        public  Single roll;
+            /// <summary> Desired pitch angle in radians </summary>
+        public  Single pitch;
+            /// <summary> Desired yaw angle in radians </summary>
+        public  Single yaw;
+            /// <summary> Collective thrust, normalized to 0 .. 1 </summary>
+        public  Single thrust;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT = 58;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=24)]
+    public struct mavlink_roll_pitch_yaw_speed_thrust_setpoint_t
+    {
+        /// <summary> Timestamp in micro seconds since unix epoch </summary>
+        public  UInt64 time_us;
+            /// <summary> Desired roll angular speed in rad/s </summary>
+        public  Single roll_speed;
+            /// <summary> Desired pitch angular speed in rad/s </summary>
+        public  Single pitch_speed;
+            /// <summary> Desired yaw angular speed in rad/s </summary>
+        public  Single yaw_speed;
+            /// <summary> Collective thrust, normalized to 0 .. 1 </summary>
+        public  Single thrust;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=26)]
+    public struct mavlink_nav_controller_output_t
+    {
+        /// <summary> Current desired roll in degrees </summary>
+        public  Single nav_roll;
+            /// <summary> Current desired pitch in degrees </summary>
+        public  Single nav_pitch;
+            /// <summary> Current desired heading in degrees </summary>
+        public  Int16 nav_bearing;
+            /// <summary> Bearing to current waypoint/target in degrees </summary>
+        public  Int16 target_bearing;
+            /// <summary> Distance to active waypoint in meters </summary>
+        public  UInt16 wp_dist;
+            /// <summary> Current altitude error in meters </summary>
+        public  Single alt_error;
+            /// <summary> Current airspeed error in meters/second </summary>
+        public  Single aspd_error;
+            /// <summary> Current crosstrack error on x-y plane in meters </summary>
+        public  Single xtrack_error;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_POSITION_TARGET = 63;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=16)]
+    public struct mavlink_position_target_t
+    {
+        /// <summary> x position </summary>
+        public  Single x;
+            /// <summary> y position </summary>
+        public  Single y;
+            /// <summary> z position </summary>
+        public  Single z;
+            /// <summary> yaw orientation in radians, 0 = NORTH </summary>
+        public  Single yaw;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_STATE_CORRECTION = 64;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=36)]
+    public struct mavlink_state_correction_t
+    {
+        /// <summary> x position error </summary>
+        public  Single xErr;
+            /// <summary> y position error </summary>
+        public  Single yErr;
+            /// <summary> z position error </summary>
+        public  Single zErr;
+            /// <summary> roll error (radians) </summary>
+        public  Single rollErr;
+            /// <summary> pitch error (radians) </summary>
+        public  Single pitchErr;
+            /// <summary> yaw error (radians) </summary>
+        public  Single yawErr;
+            /// <summary> x velocity </summary>
+        public  Single vxErr;
+            /// <summary> y velocity </summary>
+        public  Single vyErr;
+            /// <summary> z velocity </summary>
+        public  Single vzErr;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_SET_ALTITUDE = 65;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)]
+    public struct mavlink_set_altitude_t
+    {
+        /// <summary> The system setting the altitude </summary>
+        public  byte target;
+            /// <summary> The new altitude in meters </summary>
+        public  UInt32 mode;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=6)]
+    public struct mavlink_request_data_stream_t
+    {
+        /// <summary> The target requested to send the message stream. </summary>
+        public  byte target_system;
+            /// <summary> The target requested to send the message stream. </summary>
+        public  byte target_component;
+            /// <summary> The ID of the requested message type </summary>
+        public  byte req_stream_id;
+            /// <summary> Update rate in Hertz </summary>
+        public  UInt16 req_message_rate;
+            /// <summary> 1 to start sending, 0 to stop sending. </summary>
+        public  byte start_stop;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_HIL_STATE = 67;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=56)]
+    public struct mavlink_hil_state_t
+    {
+        /// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt64 usec;
+            /// <summary> Roll angle (rad) </summary>
+        public  Single roll;
+            /// <summary> Pitch angle (rad) </summary>
+        public  Single pitch;
+            /// <summary> Yaw angle (rad) </summary>
+        public  Single yaw;
+            /// <summary> Roll angular speed (rad/s) </summary>
+        public  Single rollspeed;
+            /// <summary> Pitch angular speed (rad/s) </summary>
+        public  Single pitchspeed;
+            /// <summary> Yaw angular speed (rad/s) </summary>
+        public  Single yawspeed;
+            /// <summary> Latitude, expressed as * 1E7 </summary>
+        public  Int32 lat;
+            /// <summary> Longitude, expressed as * 1E7 </summary>
+        public  Int32 lon;
+            /// <summary> Altitude in meters, expressed as * 1000 (millimeters) </summary>
+        public  Int32 alt;
+            /// <summary> Ground X Speed (Latitude), expressed as m/s * 100 </summary>
+        public  Int16 vx;
+            /// <summary> Ground Y Speed (Longitude), expressed as m/s * 100 </summary>
+        public  Int16 vy;
+            /// <summary> Ground Z Speed (Altitude), expressed as m/s * 100 </summary>
+        public  Int16 vz;
+            /// <summary> X acceleration (mg) </summary>
+        public  Int16 xacc;
+            /// <summary> Y acceleration (mg) </summary>
+        public  Int16 yacc;
+            /// <summary> Z acceleration (mg) </summary>
+        public  Int16 zacc;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_HIL_CONTROLS = 68;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=26)]
+    public struct mavlink_hil_controls_t
+    {
+        /// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
+        public  UInt64 time_us;
+            /// <summary> Control output -3 .. 1 </summary>
+        public  Single roll_ailerons;
+            /// <summary> Control output -1 .. 1 </summary>
+        public  Single pitch_elevator;
+            /// <summary> Control output -1 .. 1 </summary>
+        public  Single yaw_rudder;
+            /// <summary> Throttle 0 .. 1 </summary>
+        public  Single throttle;
+            /// <summary> System mode (MAV_MODE) </summary>
+        public  byte mode;
+            /// <summary> Navigation mode (MAV_NAV_MODE) </summary>
+        public  byte nav_mode;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_MANUAL_CONTROL = 69;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=21)]
+    public struct mavlink_manual_control_t
+    {
+        /// <summary> The system to be controlled </summary>
+        public  byte target;
+            /// <summary> roll </summary>
+        public  Single roll;
+            /// <summary> pitch </summary>
+        public  Single pitch;
+            /// <summary> yaw </summary>
+        public  Single yaw;
+            /// <summary> thrust </summary>
+        public  Single thrust;
+            /// <summary> roll control enabled auto:0, manual:1 </summary>
+        public  byte roll_manual;
+            /// <summary> pitch auto:0, manual:1 </summary>
+        public  byte pitch_manual;
+            /// <summary> yaw auto:0, manual:1 </summary>
+        public  byte yaw_manual;
+            /// <summary> thrust auto:0, manual:1 </summary>
+        public  byte thrust_manual;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+    public struct mavlink_rc_channels_override_t
+    {
+        /// <summary> System ID </summary>
+        public  byte target_system;
+            /// <summary> Component ID </summary>
+        public  byte target_component;
+            /// <summary> RC channel 1 value, in microseconds </summary>
+        public  UInt16 chan1_raw;
+            /// <summary> RC channel 2 value, in microseconds </summary>
+        public  UInt16 chan2_raw;
+            /// <summary> RC channel 3 value, in microseconds </summary>
+        public  UInt16 chan3_raw;
+            /// <summary> RC channel 4 value, in microseconds </summary>
+        public  UInt16 chan4_raw;
+            /// <summary> RC channel 5 value, in microseconds </summary>
+        public  UInt16 chan5_raw;
+            /// <summary> RC channel 6 value, in microseconds </summary>
+        public  UInt16 chan6_raw;
+            /// <summary> RC channel 7 value, in microseconds </summary>
+        public  UInt16 chan7_raw;
+            /// <summary> RC channel 8 value, in microseconds </summary>
+        public  UInt16 chan8_raw;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 73;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+    public struct mavlink_global_position_int_t
+    {
+        /// <summary> Latitude, expressed as * 1E7 </summary>
+        public  Int32 lat;
+            /// <summary> Longitude, expressed as * 1E7 </summary>
+        public  Int32 lon;
+            /// <summary> Altitude in meters, expressed as * 1000 (millimeters) </summary>
+        public  Int32 alt;
+            /// <summary> Ground X Speed (Latitude), expressed as m/s * 100 </summary>
+        public  Int16 vx;
+            /// <summary> Ground Y Speed (Longitude), expressed as m/s * 100 </summary>
+        public  Int16 vy;
+            /// <summary> Ground Z Speed (Altitude), expressed as m/s * 100 </summary>
+        public  Int16 vz;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_VFR_HUD = 74;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)]
+    public struct mavlink_vfr_hud_t
+    {
+        /// <summary> Current airspeed in m/s </summary>
+        public  Single airspeed;
+            /// <summary> Current ground speed in m/s </summary>
+        public  Single groundspeed;
+            /// <summary> Current heading in degrees, in compass units (0..360, 0=north) </summary>
+        public  Int16 heading;
+            /// <summary> Current throttle setting in integer percent, 0 to 100 </summary>
+        public  UInt16 throttle;
+            /// <summary> Current altitude (MSL), in meters </summary>
+        public  Single alt;
+            /// <summary> Current climb rate in meters/second </summary>
+        public  Single climb;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_COMMAND = 75;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=20)]
+    public struct mavlink_command_t
+    {
+        /// <summary> System which should execute the command </summary>
+        public  byte target_system;
+            /// <summary> Component which should execute the command, 0 for all components </summary>
+        public  byte target_component;
+            /// <summary> Command ID, as defined by MAV_CMD enum. </summary>
+        public  byte command;
+            /// <summary> 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) </summary>
+        public  byte confirmation;
+            /// <summary> Parameter 1, as defined by MAV_CMD enum. </summary>
+        public  Single param1;
+            /// <summary> Parameter 2, as defined by MAV_CMD enum. </summary>
+        public  Single param2;
+            /// <summary> Parameter 3, as defined by MAV_CMD enum. </summary>
+        public  Single param3;
+            /// <summary> Parameter 4, as defined by MAV_CMD enum. </summary>
+        public  Single param4;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_COMMAND_ACK = 76;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=8)]
+    public struct mavlink_command_ack_t
+    {
+        /// <summary> Current airspeed in m/s </summary>
+        public  Single command;
+            /// <summary> 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION </summary>
+        public  Single result;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_OPTICAL_FLOW = 100;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=18)]
+    public struct mavlink_optical_flow_t
+    {
+        /// <summary> Timestamp (UNIX) </summary>
+        public  UInt64 time;
+            /// <summary> Sensor ID </summary>
+        public  byte sensor_id;
+            /// <summary> Flow in pixels in x-sensor direction </summary>
+        public  Int16 flow_x;
+            /// <summary> Flow in pixels in y-sensor direction </summary>
+        public  Int16 flow_y;
+            /// <summary> Optical flow quality / confidence. 0: bad, 255: maximum quality </summary>
+        public  byte quality;
+            /// <summary> Ground distance in meters </summary>
+        public  Single ground_distance;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT = 140;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=36)]
+    public struct mavlink_object_detection_event_t
+    {
+        /// <summary> Timestamp in milliseconds since system boot </summary>
+        public  UInt32 time;
+            /// <summary> Object ID </summary>
+        public  UInt16 object_id;
+            /// <summary> Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal </summary>
+        public  byte type;
+            /// <summary> Name of the object as defined by the detector </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=20)]
+		public string name;
+            /// <summary> Detection quality / confidence. 0: bad, 255: maximum confidence </summary>
+        public  byte quality;
+            /// <summary> Angle of the object with respect to the body frame in NED coordinates in radians. 0: front </summary>
+        public  Single bearing;
+            /// <summary> Ground distance in meters </summary>
+        public  Single distance;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_DEBUG_VECT = 251;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=30)]
+    public struct mavlink_debug_vect_t
+    {
+        /// <summary> Name </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)]
+		public string name;
+            /// <summary> Timestamp </summary>
+        public  UInt64 usec;
+            /// <summary> x </summary>
+        public  Single x;
+            /// <summary> y </summary>
+        public  Single y;
+            /// <summary> z </summary>
+        public  Single z;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 252;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)]
+    public struct mavlink_named_value_float_t
+    {
+        /// <summary> Name of the debug variable </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)]
+		public string name;
+            /// <summary> Floating point value </summary>
+        public  Single value;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_NAMED_VALUE_INT = 253;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=14)]
+    public struct mavlink_named_value_int_t
+    {
+        /// <summary> Name of the debug variable </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=10)]
+		public string name;
+            /// <summary> Signed integer value </summary>
+        public  Int32 value;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_STATUSTEXT = 254;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=51)]
+    public struct mavlink_statustext_t
+    {
+        /// <summary> Severity of status, 0 = info message, 255 = critical fault </summary>
+        public  byte severity;
+            /// <summary> Status text message, without null termination character </summary>
+        [MarshalAs(UnmanagedType.ByValArray,SizeConst=50)]
+		public byte[] text;
+    
+    };
+
+
+    public const byte MAVLINK_MSG_ID_DEBUG = 255;
+    [StructLayout(LayoutKind.Sequential,Pack=1,Size=5)]
+    public struct mavlink_debug_t
+    {
+        /// <summary> index of debug variable </summary>
+        public  byte ind;
+            /// <summary> DEBUG value </summary>
+        public  Single value;
+    
+    };
+
+     }
 #endif
 }
-
diff --git a/Tools/ArdupilotMegaPlanner/MagCalib.cs b/Tools/ArdupilotMegaPlanner/MagCalib.cs
index e94a639932a9bc26d3c1ee3eaf2d0da3534e4103..199bcb4975ecf7743f80459bb5f2cb9c4da51c8f 100644
--- a/Tools/ArdupilotMegaPlanner/MagCalib.cs
+++ b/Tools/ArdupilotMegaPlanner/MagCalib.cs
@@ -98,9 +98,9 @@ namespace ArdupilotMega
                     if (packet == null)
                         continue;
 
-                    if (packet.GetType() == typeof(MAVLink.__mavlink_vfr_hud_t))
+                    if (packet.GetType() == typeof(MAVLink.mavlink_vfr_hud_t))
                     {
-                        if (((MAVLink.__mavlink_vfr_hud_t)packet).throttle >= throttleThreshold)
+                        if (((MAVLink.mavlink_vfr_hud_t)packet).throttle >= throttleThreshold)
                         {
                             useData = true;
                         }
@@ -111,35 +111,35 @@ namespace ArdupilotMega
 
                     }
 
-                    if (packet.GetType() == typeof(MAVLink.__mavlink_sensor_offsets_t))
+                    if (packet.GetType() == typeof(MAVLink.mavlink_sensor_offsets_t))
                     {
                         offset = new Tuple<float, float, float>(
-                            ((MAVLink.__mavlink_sensor_offsets_t)packet).mag_ofs_x,
-                            ((MAVLink.__mavlink_sensor_offsets_t)packet).mag_ofs_y,
-                            ((MAVLink.__mavlink_sensor_offsets_t)packet).mag_ofs_z);
+                            ((MAVLink.mavlink_sensor_offsets_t)packet).mag_ofs_x,
+                            ((MAVLink.mavlink_sensor_offsets_t)packet).mag_ofs_y,
+                            ((MAVLink.mavlink_sensor_offsets_t)packet).mag_ofs_z);
                     }
-                    else if (packet.GetType() == typeof(MAVLink.__mavlink_raw_imu_t) && useData)
+                    else if (packet.GetType() == typeof(MAVLink.mavlink_raw_imu_t) && useData)
                     {
                         int div = 20;
 
                         // fox dxf
                         vertex = new Polyline3dVertex(new Vector3f(
-                            ((MAVLink.__mavlink_raw_imu_t)packet).xmag - offset.Item1,
-                            ((MAVLink.__mavlink_raw_imu_t)packet).ymag - offset.Item2,
-                            ((MAVLink.__mavlink_raw_imu_t)packet).zmag - offset.Item3)
+                            ((MAVLink.mavlink_raw_imu_t)packet).xmag - offset.Item1,
+                            ((MAVLink.mavlink_raw_imu_t)packet).ymag - offset.Item2,
+                            ((MAVLink.mavlink_raw_imu_t)packet).zmag - offset.Item3)
                             );
                         vertexes.Add(vertex);
 
 
                         // for old method
-                        setMinorMax(((MAVLink.__mavlink_raw_imu_t)packet).xmag - offset.Item1, ref minx, ref maxx);
-                        setMinorMax(((MAVLink.__mavlink_raw_imu_t)packet).ymag - offset.Item2, ref miny, ref maxy);
-                        setMinorMax(((MAVLink.__mavlink_raw_imu_t)packet).zmag - offset.Item3, ref minz, ref maxz);
+                        setMinorMax(((MAVLink.mavlink_raw_imu_t)packet).xmag - offset.Item1, ref minx, ref maxx);
+                        setMinorMax(((MAVLink.mavlink_raw_imu_t)packet).ymag - offset.Item2, ref miny, ref maxy);
+                        setMinorMax(((MAVLink.mavlink_raw_imu_t)packet).zmag - offset.Item3, ref minz, ref maxz);
 
                         // for new lease sq
-                        string item = (int)(((MAVLink.__mavlink_raw_imu_t)packet).xmag / div) + "," +
-                            (int)(((MAVLink.__mavlink_raw_imu_t)packet).ymag / div) + "," +
-                            (int)(((MAVLink.__mavlink_raw_imu_t)packet).zmag / div);
+                        string item = (int)(((MAVLink.mavlink_raw_imu_t)packet).xmag / div) + "," +
+                            (int)(((MAVLink.mavlink_raw_imu_t)packet).ymag / div) + "," +
+                            (int)(((MAVLink.mavlink_raw_imu_t)packet).zmag / div);
 
                         if (filter.ContainsKey(item))
                         {
@@ -155,9 +155,9 @@ namespace ArdupilotMega
 
 
                         data.Add(new Tuple<float, float, float>(
-                            ((MAVLink.__mavlink_raw_imu_t)packet).xmag - offset.Item1,
-                            ((MAVLink.__mavlink_raw_imu_t)packet).ymag - offset.Item2,
-                            ((MAVLink.__mavlink_raw_imu_t)packet).zmag - offset.Item3));
+                            ((MAVLink.mavlink_raw_imu_t)packet).xmag - offset.Item1,
+                            ((MAVLink.mavlink_raw_imu_t)packet).ymag - offset.Item2,
+                            ((MAVLink.mavlink_raw_imu_t)packet).zmag - offset.Item3));
 
                     }
 
diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs
index ecf883be8541077d8d8a6324c542bf03f6c7298e..5ec4ebab68e9c0e9558198bc34af2f251a24ab24 100644
--- a/Tools/ArdupilotMegaPlanner/MainV2.cs
+++ b/Tools/ArdupilotMegaPlanner/MainV2.cs
@@ -23,6 +23,7 @@ using System.Net.Sockets;
 using IronPython.Hosting;
 using log4net;
 using ArdupilotMega.Controls;
+using System.Security.Cryptography;
 
 namespace ArdupilotMega
 {
@@ -57,6 +58,8 @@ namespace ArdupilotMega
 
         bool serialThread = false;
 
+        static internal BindingSource bs;
+
         TcpListener listener;
 
         DateTime heatbeatSend = DateTime.Now;
@@ -186,7 +189,6 @@ namespace ArdupilotMega
                 if (config["MainWidth"] != null)
                     this.Width = int.Parse(config["MainWidth"].ToString());
 
-
                 if (config["CMB_rateattitude"] != null)
                     MainV2.cs.rateattitude = byte.Parse(config["CMB_rateattitude"].ToString());
                 if (config["rateposition"] != null)
@@ -783,6 +785,12 @@ namespace ArdupilotMega
 
         private void joysticksend()
         {
+
+            float rate = 50;
+            int count = 0;
+
+            DateTime lastratechange = DateTime.Now;
+
             while (true)
             {
                 try
@@ -793,7 +801,7 @@ namespace ArdupilotMega
 
                         if (joystick != null && joystick.enabled)
                         {
-                            MAVLink.__mavlink_rc_channels_override_t rc = new MAVLink.__mavlink_rc_channels_override_t();
+                            MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t();
 
                             rc.target_component = comPort.compid;
                             rc.target_system = comPort.sysid;
@@ -815,16 +823,43 @@ namespace ArdupilotMega
                             if (joystick.getJoystickAxis(8) != Joystick.joystickaxis.None)
                                 rc.chan8_raw = cs.rcoverridech8;
 
-                            if (lastjoystick.AddMilliseconds(50) < DateTime.Now)
+                            if (lastjoystick.AddMilliseconds(rate) < DateTime.Now)
                             {
-                                //                                Console.WriteLine(DateTime.Now.Millisecond + " {0} {1} {2} {3} ", rc.chan1_raw, rc.chan2_raw, rc.chan3_raw, rc.chan4_raw);
+                                /*
+                                if (cs.rssi > 0 && cs.remrssi > 0)
+                                {
+                                    if (lastratechange.Second != DateTime.Now.Second)
+                                    {
+                                        if (cs.txbuffer > 90)
+                                        {
+                                            if (rate < 20)
+                                                rate = 21;
+                                            rate--;
+
+                                            if (cs.linkqualitygcs < 70)
+                                                rate = 50;
+                                        }
+                                        else
+                                        {
+                                            if (rate > 100)
+                                                rate = 100;
+                                            rate++;
+                                        }
+
+                                        lastratechange = DateTime.Now;
+                                    }
+                                 
+                                }
+                                 */
+//                                Console.WriteLine(DateTime.Now.Millisecond + " {0} {1} {2} {3} {4}", rc.chan1_raw, rc.chan2_raw, rc.chan3_raw, rc.chan4_raw,rate);
                                 comPort.sendPacket(rc);
+                                count++;
                                 lastjoystick = DateTime.Now;
                             }
 
                         }
                     }
-                    System.Threading.Thread.Sleep(50);
+                    System.Threading.Thread.Sleep(20);
                 }
                 catch { } // cant fall out
             }
@@ -955,11 +990,11 @@ namespace ArdupilotMega
                     {
                         //                        Console.WriteLine("remote lost {0}", cs.packetdropremote);
 
-                        MAVLink.__mavlink_heartbeat_t htb = new MAVLink.__mavlink_heartbeat_t();
+                        MAVLink.mavlink_heartbeat_t htb = new MAVLink.mavlink_heartbeat_t();
 
 #if MAVLINK10
-                        htb.type = (byte)MAVLink.MAV_TYPE.MAV_TYPE_GCS;
-                        htb.autopilot = (byte)MAVLink.MAV_AUTOPILOT.MAV_AUTOPILOT_ARDUPILOTMEGA;
+                        htb.type = (byte)MAVLink.MAV_TYPE.GCS;
+                        htb.autopilot = (byte)MAVLink.MAV_AUTOPILOT.ARDUPILOTMEGA;
                         htb.mavlink_version = 3;
 #else
                         htb.type = (byte)MAVLink.MAV_TYPE.MAV_GENERIC;
@@ -1489,6 +1524,8 @@ namespace ArdupilotMega
             var baseurl = ConfigurationManager.AppSettings["UpdateLocation"];
             string path = Path.GetFileName(Application.ExecutablePath);
 
+            path = "version.txt";
+
             // Create a request using a URL that can receive a post. 
             string requestUriString = baseurl + path;
             log.Debug("Checking for update at: " + requestUriString);
@@ -1496,7 +1533,7 @@ namespace ArdupilotMega
             webRequest.Timeout = 5000;
 
             // Set the Method property of the request to POST.
-            webRequest.Method = "HEAD";
+            webRequest.Method = "GET";
 
             ((HttpWebRequest)webRequest).IfModifiedSince = File.GetLastWriteTimeUtc(path);
 
@@ -1514,24 +1551,34 @@ namespace ArdupilotMega
             {
                 var fi = new FileInfo(path);
 
-                string CurrentEtag = "";
+                string LocalVersion = "";
+                string WebVersion = "";
 
-                if (File.Exists(path + ".etag"))
+                if (File.Exists(path))
                 {
-                    using (Stream fs = File.OpenRead(path + ".etag"))
+                    using (Stream fs = File.OpenRead(path))
                     {
                         using (StreamReader sr = new StreamReader(fs))
                         {
-                            CurrentEtag = sr.ReadLine();
+                            LocalVersion = sr.ReadLine();
                             sr.Close();
                         }
                         fs.Close();
                     }
                 }
 
-                log.Info("New file Check: " + fi.Length + " vs " + response.ContentLength + " " + response.Headers[HttpResponseHeader.ETag] + " vs " + CurrentEtag);
+                using (StreamReader sr = new StreamReader(response.GetResponseStream()))
+                {
+                    WebVersion = sr.ReadLine();
+
+                    sr.Close();
+                }
 
-                if (fi.Length != response.ContentLength || response.Headers[HttpResponseHeader.ETag] != CurrentEtag)
+
+
+                log.Info("New file Check: local " + LocalVersion + " vs Remote " + WebVersion);
+
+                if (LocalVersion != WebVersion)
                 {
                     shouldGetFile = true;
                 }
@@ -1694,7 +1741,7 @@ namespace ArdupilotMega
 
                     if (fi.Length != response.ContentLength || response.Headers[HttpResponseHeader.ETag] != CurrentEtag)
                     {
-                        using (StreamWriter sw = new StreamWriter(path + ".etag"))
+                        using (StreamWriter sw = new StreamWriter(path + ".etag.new"))
                         {
                             sw.WriteLine(response.Headers[HttpResponseHeader.ETag]);
                             sw.Close();
@@ -1795,6 +1842,42 @@ namespace ArdupilotMega
 
         }
 
+
+
+        private string GetFileETag(string fileName, DateTime modifyDate)
+        {
+
+            string FileString;
+
+            System.Text.Encoder StringEncoder;
+
+            byte[] StringBytes;
+
+            MD5CryptoServiceProvider MD5Enc;
+
+            //use file name and modify date as the unique identifier
+
+            FileString = fileName + modifyDate.ToString("d", CultureInfo.InvariantCulture);
+
+            //get string bytes
+
+            StringEncoder = Encoding.UTF8.GetEncoder();
+
+            StringBytes = new byte[StringEncoder.GetByteCount(FileString.ToCharArray(), 0, FileString.Length, true)];
+
+            StringEncoder.GetBytes(FileString.ToCharArray(), 0, FileString.Length, StringBytes, 0, true);
+
+            //hash string using MD5 and return the hex-encoded hash
+
+            MD5Enc = new MD5CryptoServiceProvider();
+
+            byte[] hash = MD5Enc.ComputeHash((Stream)File.OpenRead(fileName));
+
+            return "\"" + BitConverter.ToString(hash).Replace("-", string.Empty) + "\"";
+
+        }
+
+
         protected override bool ProcessCmdKey(ref Message msg, Keys keyData)
         {
             if (keyData == (Keys.Control | Keys.F))
@@ -1818,7 +1901,18 @@ namespace ArdupilotMega
             }
             if (keyData == (Keys.Control | Keys.A)) // test
             {
-                Form frm = new _3DRradio();
+                Form temp = new Form();
+                Control frm = new _3DRradio();
+                temp.Controls.Add(frm);
+                temp.Size = frm.Size;
+                frm.Dock = DockStyle.Fill;
+                ThemeManager.ApplyThemeTo(temp);
+                temp.Show();
+                return true;
+            }
+            if (keyData == (Keys.Control | Keys.W)) // test
+            {
+                Form frm = new GCSViews.ConfigurationView.Configuration();
                 ThemeManager.ApplyThemeTo(frm);
                 frm.Show();
                 return true;
@@ -1898,6 +1992,9 @@ namespace ArdupilotMega
 
                 if (comPort.rawlogfile != null)
                     comPort.rawlogfile.Close();
+
+                comPort.logfile = null;
+                comPort.rawlogfile = null;
             }
             catch { }
 
diff --git a/Tools/ArdupilotMegaPlanner/Mavlink/MavlinkOther.cs b/Tools/ArdupilotMegaPlanner/Mavlink/MavlinkOther.cs
new file mode 100644
index 0000000000000000000000000000000000000000..f01d258e0afa143cccb91c701ddab3f92bd52e1c
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Mavlink/MavlinkOther.cs
@@ -0,0 +1,167 @@
+using System;
+using System.Collections.Generic;
+using System.Linq;
+using System.Text;
+
+namespace ArdupilotMega
+{
+    public partial class MAVLink
+    {
+#if !MAVLINK10
+        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
+        };
+
+        public 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
+        };
+
+        public 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
+        };
+
+        public 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
+        };
+
+        public 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
+        };
+
+        public 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
+        };
+
+        public enum MAV_AUTOPILOT_TYPE
+        {
+            MAV_AUTOPILOT_GENERIC = 0,
+            MAV_AUTOPILOT_PIXHAWK = 1,
+            MAV_AUTOPILOT_SLUGS = 2,
+            MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
+            MAV_AUTOPILOT_NONE = 4
+        };
+
+        public 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
+        };
+
+        public enum MAV_FRAME
+        {
+            GLOBAL = 0,
+            LOCAL = 1,
+            MISSION = 2,
+            GLOBAL_RELATIVE_ALT = 3,
+            LOCAL_ENU = 4
+        };
+
+#endif
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs
index 73f5cfac07b7032e975e773150f84a51a1e046a6..2f1a7a8c8febf0e0752f686ead744d670159cb1f 100644
--- a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs
+++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs
@@ -38,6 +38,8 @@ namespace ArdupilotMega
 
         Hashtable data = new Hashtable();
 
+        PointLatLngAlt homepos = new PointLatLngAlt();
+
         public MavlinkLog()
         {
             InitializeComponent();
@@ -576,15 +578,16 @@ namespace ArdupilotMega
 
 
             OpenFileDialog openFileDialog1 = new OpenFileDialog();
-            openFileDialog1.Filter = "*.tlog|*.tlog";
-            openFileDialog1.FilterIndex = 2;
-            openFileDialog1.RestoreDirectory = true;
-            openFileDialog1.Multiselect = false;
             try
             {
-                openFileDialog1.InitialDirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar;
+              //  openFileDialog1.InitialDirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar;
             }
             catch { } // incase dir doesnt exist
+            openFileDialog1.Filter = "*.tlog|*.tlog";
+            openFileDialog1.FilterIndex = 2;
+            openFileDialog1.RestoreDirectory = true;
+            openFileDialog1.Multiselect = false;
+
 
             if (openFileDialog1.ShowDialog() == DialogResult.OK)
             {
@@ -744,7 +747,7 @@ namespace ArdupilotMega
                 int colorvalue = ColourValues[step % ColourValues.Length];
                 step++;
 
-                myCurve = zg1.GraphPane.AddCurve(lookforfields[a].Replace("__mavlink_", ""), lists[a], Color.FromArgb(unchecked(colorvalue + (int)0xff000000)), SymbolType.None);
+                myCurve = zg1.GraphPane.AddCurve(lookforfields[a].Replace("mavlink_", ""), lists[a], Color.FromArgb(unchecked(colorvalue + (int)0xff000000)), SymbolType.None);
 
                 double xMin, xMax, yMin, yMax;
 
@@ -781,6 +784,8 @@ namespace ArdupilotMega
 
                 MavlinkInterface.packets.Initialize(); // clear
 
+                CurrentState cs = new CurrentState();
+
                 // to get first packet time
                 MavlinkInterface.readPacket();
 
@@ -793,8 +798,18 @@ namespace ArdupilotMega
 
                     byte[] packet = MavlinkInterface.readPacket();
 
+                    cs.datetime = MavlinkInterface.lastlogread;
+
+                    cs.UpdateCurrentSettings(null, true, MavlinkInterface);
+
                     object data = MavlinkInterface.DebugPacket(packet, false);
 
+                    if (data == null)
+                    {
+                        log.Info("No info on packet");
+                        continue;
+                    }
+
                     Type test = data.GetType();
 
                     foreach (var field in test.GetFields())
@@ -858,6 +873,8 @@ namespace ArdupilotMega
 
                     addMagField(ref options);
 
+                    addDistHome(ref options);
+
                 }
                 catch (Exception ex) { log.Info(ex.ToString()); }
 
@@ -865,10 +882,14 @@ namespace ArdupilotMega
                 //options.Sort(delegate(string c1, string c2) { return String.Compare(c1.Substring(0,c1.IndexOf('.')),c2.Substring(0,c2.IndexOf('.')));});
 
                 // this needs sorting
+                string lastitem = "";
                 foreach (string item in options)
                 {
                     var items = item.Split('.');
+                    if (items[0] != lastitem)
+                        AddHeader(selectform, items[0].Replace("mavlink_","").Replace("_t","").ToUpper());
                     AddDataOption(selectform, items[1] + " " + items[0]);
+                    lastitem = items[0];
                 }
 
                 selectform.Show();
@@ -880,6 +901,29 @@ namespace ArdupilotMega
             return selection;
         }
 
+        void dospecial(string PacketName)
+        {
+            string test = @"0; float test = (float)Sin(55) + 10; 
+test += (float)sin(45);
+return test;
+";
+
+            object answer = CodeGen.runCode(test);
+
+            Console.WriteLine(answer);
+        }
+
+        PointPairList GetValuesForField(string name)
+        {
+            // eg RAW_IMU.xmag to "xmag mavlink_raw_imu_t"
+
+            string[] items = name.ToLower().Split(new char[] {'.',' '});
+
+            PointPairList list = ((PointPairList)this.data[items[1] + " mavlink_" + items[0] + "_t"]);
+
+            return list;
+        }
+
         void addMagField(ref List<string> options)
         {
             string field = "mag_field Custom";
@@ -890,9 +934,9 @@ namespace ArdupilotMega
 
             PointPairList list = ((PointPairList)this.data[field]);
 
-            PointPairList listx = ((PointPairList)this.data["xmag __mavlink_raw_imu_t"]);
-            PointPairList listy = ((PointPairList)this.data["ymag __mavlink_raw_imu_t"]);
-            PointPairList listz = ((PointPairList)this.data["zmag __mavlink_raw_imu_t"]);
+            PointPairList listx = ((PointPairList)this.data["xmag mavlink_raw_imu_t"]);
+            PointPairList listy = ((PointPairList)this.data["ymag mavlink_raw_imu_t"]);
+            PointPairList listz = ((PointPairList)this.data["zmag mavlink_raw_imu_t"]);
 
             //(float)Math.Sqrt(Math.Pow(mx, 2) + Math.Pow(my, 2) + Math.Pow(mz, 2));
 
@@ -907,6 +951,72 @@ namespace ArdupilotMega
             }
         }
 
+        void addDistHome(ref List<string> options)
+        {
+            string field = "dist_home Custom";
+
+            options.Add("Custom.dist_home");
+
+            this.data[field] = new PointPairList();
+
+            PointLatLngAlt home = new PointLatLngAlt();
+
+            PointPairList list = ((PointPairList)this.data[field]);
+
+            PointPairList listfix = ((PointPairList)this.data["fix_type mavlink_gps_raw_t"]);
+            PointPairList listx = ((PointPairList)this.data["lat mavlink_gps_raw_t"]);
+            PointPairList listy = ((PointPairList)this.data["lon mavlink_gps_raw_t"]);
+            PointPairList listz = ((PointPairList)this.data["alt mavlink_gps_raw_t"]);
+
+            for (int a = 0; a < listfix.Count; a++)
+            {
+                if (listfix[a].Y == 2)
+                {
+                    home = new PointLatLngAlt(listx[a].Y, listy[a].Y, listz[a].Y,"Home");
+                    break;
+                }
+            }
+
+            //(float)Math.Sqrt(Math.Pow(mx, 2) + Math.Pow(my, 2) + Math.Pow(mz, 2));
+
+            for (int a = 0; a < listx.Count; a++)
+            {
+
+                double ans = home.GetDistance(new PointLatLngAlt(listx[a].Y, listy[a].Y, listz[a].Y, "Point"));
+
+                //Console.WriteLine("{0} {1} {2} {3}", ans, listx[a].Y, listy[a].Y, listz[a].Y);
+
+                list.Add(listx[a].X, ans);
+            }
+        }
+
+        private void AddHeader(Form selectform, string Name)
+        {
+            System.Windows.Forms.Label lbl_head = new System.Windows.Forms.Label();
+
+            log.Info("Add Header " + Name);
+
+            lbl_head.Text = Name;
+            lbl_head.Name = Name;
+            lbl_head.Location = new System.Drawing.Point(x, y);
+            lbl_head.Size = new System.Drawing.Size(100, 20);
+
+            selectform.Controls.Add(lbl_head);
+
+            Application.DoEvents();
+
+            x += 0;
+            y += 20;
+
+            if (y > selectform.Height - 60)
+            {
+                x += 100;
+                y = 10;
+
+                selectform.Width = x + 100;
+            }
+        }
+
         private void AddDataOption(Form selectform, string Name)
         {
 
@@ -919,6 +1029,7 @@ namespace ArdupilotMega
             chk_box.Location = new System.Drawing.Point(x, y);
             chk_box.Size = new System.Drawing.Size(100, 20);
             chk_box.CheckedChanged += new EventHandler(chk_box_CheckedChanged);
+            chk_box.MouseUp += new MouseEventHandler(chk_box_MouseUp);
 
             selectform.Controls.Add(chk_box);
 
@@ -927,7 +1038,7 @@ namespace ArdupilotMega
             x += 0;
             y += 20;
 
-            if (y > selectform.Height - 50)
+            if (y > selectform.Height - 60)
             {
                 x += 100;
                 y = 10;
@@ -936,7 +1047,26 @@ namespace ArdupilotMega
             }
         }
 
+        void chk_box_MouseUp(object sender, MouseEventArgs e)
+        {
+            if (e.Button == System.Windows.Forms.MouseButtons.Right)
+            {
+                // dont action a already draw item
+                if (!((CheckBox)sender).Checked)
+                {
+                    rightclick = true;
+                    ((CheckBox)sender).Checked = true;
+                }
+                else
+                {
+                    ((CheckBox)sender).Checked = false;
+                }
+                rightclick = false;
+            }
+        }
+
         int colorStep = 0;
+        bool rightclick = false;
 
         void chk_box_CheckedChanged(object sender, EventArgs e)
         {
@@ -949,13 +1079,13 @@ namespace ArdupilotMega
                 int colorvalue = ColourValues[colorStep % ColourValues.Length];
                 colorStep++;
 
-                myCurve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name.Replace("__mavlink_", ""), (PointPairList)data[((CheckBox)sender).Name], Color.FromArgb(unchecked(colorvalue + (int)0xff000000)), SymbolType.None);
+                myCurve = zg1.GraphPane.AddCurve(((CheckBox)sender).Name.Replace("mavlink_", ""), (PointPairList)data[((CheckBox)sender).Name], Color.FromArgb(unchecked(colorvalue + (int)0xff000000)), SymbolType.None);
 
                 myCurve.Tag = ((CheckBox)sender).Name;
 
-                if (myCurve.Tag.ToString() == "roll __mavlink_attitude_t" ||
-                    myCurve.Tag.ToString() == "pitch __mavlink_attitude_t" ||
-                    myCurve.Tag.ToString() == "yaw __mavlink_attitude_t")
+                if (myCurve.Tag.ToString() == "roll mavlink_attitude_t" ||
+                    myCurve.Tag.ToString() == "pitch mavlink_attitude_t" ||
+                    myCurve.Tag.ToString() == "yaw mavlink_attitude_t")
                 {
                     PointPairList ppl = new PointPairList((PointPairList)data[((CheckBox)sender).Name]);
                     for (int a = 0; a < ppl.Count; a++)
@@ -970,11 +1100,13 @@ namespace ArdupilotMega
 
                 myCurve.GetRange(out xMin, out xMax, out yMin, out  yMax, true, false, zg1.GraphPane);
 
-                if (yMin > 900 && yMax < 2100 && yMin < 2100)
+                if (rightclick || (yMin > 850 && yMax < 2100 && yMin < 2100))
                 {
                     myCurve.IsY2Axis = true;
                     myCurve.YAxisIndex = 0;
                     zg1.GraphPane.Y2Axis.IsVisible = true;
+
+                    myCurve.Label.Text = myCurve.Label.Text + "-R";
                 }
             }
             else
@@ -995,6 +1127,8 @@ namespace ArdupilotMega
                 // fix new line types
                 ThemeManager.ApplyThemeTo(this);
 
+                zg1.GraphPane.XAxis.AxisGap = 0;
+
                 zg1.Invalidate();
                 zg1.AxisChange();
             }
@@ -1018,18 +1152,10 @@ namespace ArdupilotMega
             x = 10;
             y = 10;
 
-            {
-                CheckBox chk_box = new CheckBox();
-                chk_box.Text = "Logarithmic";
-                chk_box.Name = "Logarithmic";
-                chk_box.Location = new System.Drawing.Point(x, y);
-                chk_box.Size = new System.Drawing.Size(100, 20);
-                //chk_box.CheckedChanged += new EventHandler(chk_log_CheckedChanged);
-
-                selectform.Controls.Add(chk_box);
-            }
-
-            y += 20;
+            AddHeader(selectform, "Left Click");
+            AddHeader(selectform, "Left Axis");
+            AddHeader(selectform, "Right Click");
+            AddHeader(selectform, "Right Axis");
 
             ThemeManager.ApplyThemeTo(selectform);
 
diff --git a/Tools/ArdupilotMegaPlanner/Msi/.gitignore b/Tools/ArdupilotMegaPlanner/Msi/.gitignore
new file mode 100644
index 0000000000000000000000000000000000000000..197dac0b4840050d00324d31eb99667501657842
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Msi/.gitignore
@@ -0,0 +1,4 @@
+
+*.msi
+*.wixpdb
+*.wixobj
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Msi/installer.bat b/Tools/ArdupilotMegaPlanner/Msi/installer.bat
new file mode 100644
index 0000000000000000000000000000000000000000..a24e75791b41e36bebcbb4717989b1727ff89afc
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Msi/installer.bat
@@ -0,0 +1,16 @@
+@echo off
+
+wix.exe ..\bin\release\
+
+del installer.wixobj
+
+"%wix%\bin\candle" installer.wxs -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension
+
+
+"%wix%\bin\light" installer.wixobj "%wix%\bin\difxapp_x86.wixlib" -o APMPlanner32.msi -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension
+
+
+"%wix%\bin\light" installer.wixobj "%wix%\bin\difxapp_x64.wixlib" -o APMPlanner64.msi -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension
+
+
+pause
diff --git a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs
new file mode 100644
index 0000000000000000000000000000000000000000..b30f164d295455e05987c25372143ce92a6411a2
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs
@@ -0,0 +1,338 @@
+<?xml version="1.0" encoding="utf-8"?>
+<Wix xmlns="http://schemas.microsoft.com/wix/2006/wi" xmlns:netfx="http://schemas.microsoft.com/wix/NetFxExtension" xmlns:difx="http://schemas.microsoft.com/wix/DifxAppExtension">
+
+
+    <Product Id="*" Name="APM Planner" Language="1033" Version="1.1.63" Manufacturer="Michael Oborne" UpgradeCode="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
+
+        <Package Description="APM Planner Installer" Comments="Apm Planner Installer" Manufacturer="Michael Oborne" InstallerVersion="200" Compressed="yes" />
+
+
+<Upgrade Id="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
+    <UpgradeVersion OnlyDetect="yes" Minimum="1.1.63" Property="NEWERVERSIONDETECTED" IncludeMinimum="no" />
+    <UpgradeVersion OnlyDetect="no" Maximum="1.1.63" Property="OLDERVERSIONBEINGUPGRADED" IncludeMaximum="no" />
+</Upgrade>
+
+<InstallExecuteSequence>
+    <RemoveExistingProducts After="InstallInitialize" />
+</InstallExecuteSequence>
+
+        <PropertyRef Id="NETFRAMEWORK35" />
+
+        <Condition Message="This application requires .NET Framework 3.5. Please install the .NET Framework then run this installer again."><![CDATA[Installed OR NETFRAMEWORK35]]></Condition>
+
+        <Media Id="1" Cabinet="product.cab" EmbedCab="yes" />
+
+        <Directory Id="TARGETDIR" Name="SourceDir">
+            <Directory Id="ProgramFilesFolder" Name="PFiles">
+                
+<Directory Id="APMPlanner" Name="APM Planner">
+<Component Id="InstallDirPermissions" Guid="{525389D7-EB3C-4d77-A5F6-A285CF99437D}" KeyPath="yes"> 
+                        <CreateFolder> 
+                            <Permission User="Everyone" GenericAll="yes" /> 
+                        </CreateFolder>
+                    </Component>
+<Component Id="_comp1" Guid="27583d32-d5cc-422a-a1d9-22fcb0aaf864">
+<File Id="_2" Source="..\bin\release\AeroSimRCAPMHil.zip" />
+<File Id="_3" Source="..\bin\release\alglibnet2.dll" />
+<File Id="_4" Source="..\bin\release\ArduCopter-sitl.exe" />
+<File Id="_5" Source="..\bin\release\arducopter-xplane.zip" />
+<File Id="_6" Source="..\bin\release\ArduCopter.exe" />
+<File Id="_7" Source="..\bin\release\ArdupilotMegaPlanner.exe" />
+<File Id="_8" Source="..\bin\release\ArdupilotMegaPlanner.exe.config" />
+<File Id="_9" Source="..\bin\release\ArdupilotMegaPlanner.pdb" />
+<File Id="_10" Source="..\bin\release\ArduPlane-sitl.exe" />
+<File Id="_11" Source="..\bin\release\ArduPlane.exe" />
+<File Id="_12" Source="..\bin\release\block_plane_0.dae" />
+<File Id="_13" Source="..\bin\release\BSE.Windows.Forms.dll" />
+<File Id="_14" Source="..\bin\release\Core.dll" />
+<File Id="_15" Source="..\bin\release\cygwin1.dll" />
+<File Id="_16" Source="..\bin\release\dataflashlog.xml" />
+<File Id="_17" Source="..\bin\release\DirectShowLib-2005.dll" />
+<File Id="_18" Source="..\bin\release\eeprom.bin" />
+<File Id="_19" Source="..\bin\release\GMap.NET.Core.dll" />
+<File Id="_20" Source="..\bin\release\GMap.NET.WindowsForms.dll" />
+<File Id="_21" Source="..\bin\release\hud.html" />
+<File Id="_22" Source="..\bin\release\ICSharpCode.SharpZipLib.dll" />
+<File Id="_23" Source="..\bin\release\Ionic.Zip.Reduced.dll" />
+<File Id="_24" Source="..\bin\release\IronPython.dll" />
+<File Id="_25" Source="..\bin\release\IronPython.Modules.dll" />
+<File Id="_26" Source="..\bin\release\JSBSim.exe" />
+<File Id="_27" Source="..\bin\release\KMLib.dll" />
+<File Id="_28" Source="..\bin\release\log4net.dll" />
+<File Id="_29" Source="..\bin\release\mavcmd.xml" />
+<File Id="_30" Source="..\bin\release\MAVLink.xml" />
+<File Id="_31" Source="..\bin\release\MetaDataExtractor.dll" />
+<File Id="_32" Source="..\bin\release\Microsoft.DirectX.DirectInput.dll" />
+<File Id="_33" Source="..\bin\release\Microsoft.DirectX.dll" />
+<File Id="_34" Source="..\bin\release\Microsoft.Dynamic.dll" />
+<File Id="_35" Source="..\bin\release\Microsoft.Scripting.Core.dll" />
+<File Id="_36" Source="..\bin\release\Microsoft.Scripting.Debugging.dll" />
+<File Id="_37" Source="..\bin\release\Microsoft.Scripting.dll" />
+<File Id="_38" Source="..\bin\release\Microsoft.Scripting.ExtensionAttribute.dll" />
+<File Id="_39" Source="..\bin\release\netDxf.dll" />
+<File Id="_40" Source="..\bin\release\OpenTK.dll" />
+<File Id="_41" Source="..\bin\release\OpenTK.GLControl.dll" />
+<File Id="_42" Source="..\bin\release\quadhil.xml" />
+<File Id="_43" Source="..\bin\release\serialsent.raw" />
+<File Id="_44" Source="..\bin\release\SharpKml.dll" />
+<File Id="_45" Source="..\bin\release\System.Data.SQLite.dll" />
+<File Id="_46" Source="..\bin\release\System.Speech.dll" />
+<File Id="_47" Source="..\bin\release\Updater.exe" />
+<File Id="_48" Source="..\bin\release\Updater.exe.config" />
+<File Id="_49" Source="..\bin\release\Updater.pdb" />
+<File Id="_50" Source="..\bin\release\version.exe" />
+<File Id="_51" Source="..\bin\release\version.txt" />
+<File Id="_52" Source="..\bin\release\ZedGraph.dll" />
+</Component>
+<Directory Id="aircraft52" Name="aircraft">
+<Component Id="_comp53" Guid="f064b576-e9b4-41d2-8b08-49172818c653">
+<File Id="_54" Source="..\bin\release\aircraft\placeholder.txt" />
+</Component>
+<Directory Id="arducopter54" Name="arducopter">
+<Component Id="_comp55" Guid="4d8cdb81-fab2-4b24-ad08-cefb45253f27">
+<File Id="_56" Source="..\bin\release\aircraft\arducopter\arducopter-set.xml" />
+<File Id="_57" Source="..\bin\release\aircraft\arducopter\arducopter.jpg" />
+<File Id="_58" Source="..\bin\release\aircraft\arducopter\arducopter.xml" />
+<File Id="_59" Source="..\bin\release\aircraft\arducopter\initfile.xml" />
+<File Id="_60" Source="..\bin\release\aircraft\arducopter\plus_quad2-set.xml" />
+<File Id="_61" Source="..\bin\release\aircraft\arducopter\plus_quad2.xml" />
+<File Id="_62" Source="..\bin\release\aircraft\arducopter\quad.nas" />
+<File Id="_63" Source="..\bin\release\aircraft\arducopter\README" />
+</Component>
+<Directory Id="data63" Name="data">
+<Component Id="_comp64" Guid="498fb8f9-f963-489b-bffd-605d6f70d7b1">
+<File Id="_65" Source="..\bin\release\aircraft\arducopter\data\arducopter_half_step.txt" />
+<File Id="_66" Source="..\bin\release\aircraft\arducopter\data\arducopter_step.txt" />
+<File Id="_67" Source="..\bin\release\aircraft\arducopter\data\rw_generic_pylon.ac" />
+</Component>
+</Directory>
+<Directory Id="Engines67" Name="Engines">
+<Component Id="_comp68" Guid="0844f5b1-b990-43f3-a3e0-1f123d6af8f2">
+<File Id="_69" Source="..\bin\release\aircraft\arducopter\Engines\a2830-12.xml" />
+<File Id="_70" Source="..\bin\release\aircraft\arducopter\Engines\prop10x4.5.xml" />
+</Component>
+</Directory>
+<Directory Id="Models70" Name="Models">
+<Component Id="_comp71" Guid="cead5c2b-aad8-4b6d-af62-bc3cae0ffe23">
+<File Id="_72" Source="..\bin\release\aircraft\arducopter\Models\arducopter.ac" />
+<File Id="_73" Source="..\bin\release\aircraft\arducopter\Models\arducopter.xml" />
+<File Id="_74" Source="..\bin\release\aircraft\arducopter\Models\plus_quad.ac" />
+<File Id="_75" Source="..\bin\release\aircraft\arducopter\Models\plus_quad2.ac" />
+<File Id="_76" Source="..\bin\release\aircraft\arducopter\Models\plus_quad2.xml" />
+<File Id="_77" Source="..\bin\release\aircraft\arducopter\Models\quad.3ds" />
+<File Id="_78" Source="..\bin\release\aircraft\arducopter\Models\shareware_output.3ds" />
+<File Id="_79" Source="..\bin\release\aircraft\arducopter\Models\Untitled.ac" />
+<File Id="_80" Source="..\bin\release\aircraft\arducopter\Models\Y6_test.ac" />
+</Component>
+</Directory>
+</Directory>
+<Directory Id="Rascal80" Name="Rascal">
+<Component Id="_comp81" Guid="63e7949e-2944-4ed6-849b-7a7fa45b08f7">
+<File Id="_82" Source="..\bin\release\aircraft\Rascal\Rascal-keyboard.xml" />
+<File Id="_83" Source="..\bin\release\aircraft\Rascal\Rascal-submodels.xml" />
+<File Id="_84" Source="..\bin\release\aircraft\Rascal\Rascal.xml" />
+<File Id="_85" Source="..\bin\release\aircraft\Rascal\Rascal110-JSBSim-set.xml" />
+<File Id="_86" Source="..\bin\release\aircraft\Rascal\Rascal110-JSBSim.xml" />
+<File Id="_87" Source="..\bin\release\aircraft\Rascal\Rascal110-splash.rgb" />
+<File Id="_88" Source="..\bin\release\aircraft\Rascal\README.Rascal" />
+<File Id="_89" Source="..\bin\release\aircraft\Rascal\reset_CMAC.xml" />
+<File Id="_90" Source="..\bin\release\aircraft\Rascal\thumbnail.jpg" />
+</Component>
+<Directory Id="Dialogs90" Name="Dialogs">
+<Component Id="_comp91" Guid="0e97ffbb-624b-4f93-a2c9-d58462cb82eb">
+<File Id="_92" Source="..\bin\release\aircraft\Rascal\Dialogs\config.xml" />
+<File Id="_93" Source="..\bin\release\aircraft\Rascal\Dialogs\config.xml.new" />
+</Component>
+</Directory>
+<Directory Id="Engines93" Name="Engines">
+<Component Id="_comp94" Guid="8273a711-606c-47ba-8595-78b5b9b51f84">
+<File Id="_95" Source="..\bin\release\aircraft\Rascal\Engines\18x8.xml" />
+<File Id="_96" Source="..\bin\release\aircraft\Rascal\Engines\18x8.xml.new" />
+<File Id="_97" Source="..\bin\release\aircraft\Rascal\Engines\Zenoah_G-26A.xml" />
+<File Id="_98" Source="..\bin\release\aircraft\Rascal\Engines\Zenoah_G-26A.xml.new" />
+</Component>
+</Directory>
+<Directory Id="Models98" Name="Models">
+<Component Id="_comp99" Guid="7f01cb3c-7f32-44ba-bbff-1291cef53ea4">
+<File Id="_100" Source="..\bin\release\aircraft\Rascal\Models\Rascal.rgb" />
+<File Id="_101" Source="..\bin\release\aircraft\Rascal\Models\Rascal.rgb.new" />
+<File Id="_102" Source="..\bin\release\aircraft\Rascal\Models\Rascal110-000-013.ac" />
+<File Id="_103" Source="..\bin\release\aircraft\Rascal\Models\Rascal110-000-013.ac.new" />
+<File Id="_104" Source="..\bin\release\aircraft\Rascal\Models\Rascal110.xml" />
+<File Id="_105" Source="..\bin\release\aircraft\Rascal\Models\Rascal110.xml.new" />
+<File Id="_106" Source="..\bin\release\aircraft\Rascal\Models\smoke.png" />
+<File Id="_107" Source="..\bin\release\aircraft\Rascal\Models\smoke.png.new" />
+<File Id="_108" Source="..\bin\release\aircraft\Rascal\Models\smokeW.xml" />
+<File Id="_109" Source="..\bin\release\aircraft\Rascal\Models\smokeW.xml.new" />
+<File Id="_110" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.ac" />
+<File Id="_111" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.ac.new" />
+<File Id="_112" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.xml" />
+<File Id="_113" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.xml.new" />
+</Component>
+</Directory>
+<Directory Id="Systems113" Name="Systems">
+<Component Id="_comp114" Guid="c86479fa-e506-4548-9e69-1e25a49d2a80">
+<File Id="_115" Source="..\bin\release\aircraft\Rascal\Systems\110-autopilot.xml" />
+<File Id="_116" Source="..\bin\release\aircraft\Rascal\Systems\110-autopilot.xml.new" />
+<File Id="_117" Source="..\bin\release\aircraft\Rascal\Systems\airdata.nas" />
+<File Id="_118" Source="..\bin\release\aircraft\Rascal\Systems\airdata.nas.new" />
+<File Id="_119" Source="..\bin\release\aircraft\Rascal\Systems\electrical.xml" />
+<File Id="_120" Source="..\bin\release\aircraft\Rascal\Systems\electrical.xml.new" />
+<File Id="_121" Source="..\bin\release\aircraft\Rascal\Systems\main.nas" />
+<File Id="_122" Source="..\bin\release\aircraft\Rascal\Systems\main.nas.new" />
+<File Id="_123" Source="..\bin\release\aircraft\Rascal\Systems\ugear.nas" />
+</Component>
+</Directory>
+</Directory>
+</Directory>
+<Directory Id="Driver123" Name="Driver">
+<Component Id="_comp124" Guid="1ead128f-9773-4e64-85a6-794cc19a761a">
+<File Id="_125" Source="..\bin\release\Driver\Arduino MEGA 2560.inf" />
+<File Id="_126" Source="..\bin\release\Driver\Arduino MEGA 2560.inf.new" />
+</Component>
+</Directory>
+<Directory Id="es_ES126" Name="es-ES">
+<Component Id="_comp127" Guid="804df9a1-a600-479f-90c0-d009f7b28d64">
+<File Id="_128" Source="..\bin\release\es-ES\ArdupilotMegaPlanner.resources.dll" />
+</Component>
+</Directory>
+<Directory Id="fr128" Name="fr">
+<Component Id="_comp129" Guid="2e5d2e24-cc1b-454a-bd74-ae2db91ceaa5">
+<File Id="_130" Source="..\bin\release\fr\ArdupilotMegaPlanner.resources.dll" />
+</Component>
+</Directory>
+<Directory Id="it_IT130" Name="it-IT">
+<Component Id="_comp131" Guid="ed5edb47-dda4-44e2-99b5-a7800c8509ea">
+<File Id="_132" Source="..\bin\release\it-IT\ArdupilotMegaPlanner.resources.dll" />
+</Component>
+</Directory>
+<Directory Id="jsbsim132" Name="jsbsim">
+<Component Id="_comp133" Guid="6ad32fa2-5d4f-4aa2-a6b5-c0ab66ec4c4f">
+<File Id="_134" Source="..\bin\release\jsbsim\fgout.xml" />
+<File Id="_135" Source="..\bin\release\jsbsim\rascal_test.xml" />
+</Component>
+</Directory>
+<Directory Id="m3u135" Name="m3u">
+<Component Id="_comp136" Guid="829a6282-d9c2-4ec2-959d-7695ac34c648">
+<File Id="_137" Source="..\bin\release\m3u\both.m3u" />
+<File Id="_138" Source="..\bin\release\m3u\hud.m3u" />
+<File Id="_139" Source="..\bin\release\m3u\map.m3u" />
+<File Id="_140" Source="..\bin\release\m3u\networklink.kml" />
+</Component>
+</Directory>
+<Directory Id="pl140" Name="pl">
+<Component Id="_comp141" Guid="640061ad-2bd3-495b-bfa1-6990d087b35a">
+<File Id="_142" Source="..\bin\release\pl\ArdupilotMegaPlanner.resources.dll" />
+</Component>
+</Directory>
+<Directory Id="Resources142" Name="Resources">
+<Component Id="_comp143" Guid="60f0d36e-6671-48a3-b87c-2e31a3fc50a5">
+<File Id="_144" Source="..\bin\release\Resources\MAVCmd.txt" />
+<File Id="_145" Source="..\bin\release\Resources\MAVCmd.txt.new" />
+<File Id="_146" Source="..\bin\release\Resources\Welcome_to_Michael_Oborne.rtf" />
+<File Id="_147" Source="..\bin\release\Resources\Welcome_to_Michael_Oborne.rtf.new" />
+</Component>
+</Directory>
+<Directory Id="ru_RU147" Name="ru-RU">
+<Component Id="_comp148" Guid="039b8419-4534-43d0-af2f-1418890dd3d6">
+<File Id="_149" Source="..\bin\release\ru-RU\ArdupilotMegaPlanner.resources.dll" />
+</Component>
+</Directory>
+<Directory Id="zh_Hans149" Name="zh-Hans">
+<Component Id="_comp150" Guid="287da807-7260-47c2-b782-b376d95ce68e">
+<File Id="_151" Source="..\bin\release\zh-Hans\ArdupilotMegaPlanner.resources.dll" />
+</Component>
+</Directory>
+<Directory Id="zh_TW151" Name="zh-TW">
+<Component Id="_comp152" Guid="87db4ac6-634b-4502-a649-ed59566fd6fe">
+<File Id="_153" Source="..\bin\release\zh-TW\ArdupilotMegaPlanner.resources.dll" />
+</Component>
+</Directory>
+
+                    
+                    <Directory Id="drivers" Name="Drivers">
+                        <Component Id="MyDriver" Guid="{6AC8226E-A005-437e-A3CD-0FC32D9A346F}">
+                            <File Id="apm2inf"  Source="..\Driver\Arduino MEGA 2560.inf" />
+                            <difx:Driver AddRemovePrograms='no' Legacy="yes" PlugAndPlayPrompt="no" />
+                        </Component>
+                    </Directory>
+                </Directory>
+            </Directory>
+
+            <Directory Id="ProgramMenuFolder">
+                <Directory Id="ApplicationProgramsFolder" Name="APM Planner" />
+            </Directory>
+
+        </Directory>
+
+        <DirectoryRef Id="ApplicationProgramsFolder">
+            <Component Id="ApplicationShortcut" Guid="{8BC628BA-08A0-43d6-88C8-D4C007AC4607}">
+                <Shortcut Id="ApplicationStartMenuShortcut" Name="APM Planner" Description="Ardupilot Mega Planner" Target="[APMPlanner]ArdupilotMegaPlanner.exe" WorkingDirectory="APMPlanner" />
+                <RemoveFolder Id="ApplicationProgramsFolder" On="uninstall" />
+
+                <Shortcut Id="UninstallProduct" Name="Uninstall APM Planner" Description="Uninstalls My Application" Target="[System64Folder]msiexec.exe" Arguments="/x [ProductCode]" />
+
+
+
+                <RegistryValue Root="HKCU" Key="Software\MichaelOborne\APMPlanner" Name="installed" Type="integer" Value="1" KeyPath="yes" />
+
+
+
+
+            </Component>
+        </DirectoryRef>
+
+
+        <Feature Id="MyFeature" Title="My 1st Feature" Level="1">
+            <ComponentRef Id="InstallDirPermissions" />
+
+<ComponentRef Id="_comp1" />
+<ComponentRef Id="_comp53" />
+<ComponentRef Id="_comp55" />
+<ComponentRef Id="_comp64" />
+<ComponentRef Id="_comp68" />
+<ComponentRef Id="_comp71" />
+<ComponentRef Id="_comp81" />
+<ComponentRef Id="_comp91" />
+<ComponentRef Id="_comp94" />
+<ComponentRef Id="_comp99" />
+<ComponentRef Id="_comp114" />
+<ComponentRef Id="_comp124" />
+<ComponentRef Id="_comp127" />
+<ComponentRef Id="_comp129" />
+<ComponentRef Id="_comp131" />
+<ComponentRef Id="_comp133" />
+<ComponentRef Id="_comp136" />
+<ComponentRef Id="_comp141" />
+<ComponentRef Id="_comp143" />
+<ComponentRef Id="_comp148" />
+<ComponentRef Id="_comp150" />
+<ComponentRef Id="_comp152" />
+
+            
+            <ComponentRef Id="ApplicationShortcut" />
+            <ComponentRef Id="MyDriver" />
+        </Feature>
+
+        
+            <!-- Step 2: Add UI to your installer / Step 4: Trigger the custom action -->
+    <Property Id="WIXUI_INSTALLDIR" Value="APMPlanner" />
+
+    <UI>
+        <UIRef Id="WixUI_InstallDir" />
+        <Publish Dialog="ExitDialog" 
+            Control="Finish" 
+            Event="DoAction" 
+            Value="LaunchApplication">WIXUI_EXITDIALOGOPTIONALCHECKBOX = 1 and NOT Installed</Publish>
+    </UI>
+    <Property Id="WIXUI_EXITDIALOGOPTIONALCHECKBOXTEXT" Value="Launch APM Planner" />
+
+    <!-- Step 3: Include the custom action -->
+    <Property Id="WixShellExecTarget" Value="[#_7]" />
+    <CustomAction Id="LaunchApplication" 
+        BinaryKey="WixCA" 
+        DllEntry="WixShellExec"
+        Impersonate="yes" />
+    </Product>
+    
+</Wix>
diff --git a/Tools/ArdupilotMegaPlanner/Msi/originstaller.wxs b/Tools/ArdupilotMegaPlanner/Msi/originstaller.wxs
new file mode 100644
index 0000000000000000000000000000000000000000..111a7cbfd5f28eea3e55afcdd014e0572df9c063
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Msi/originstaller.wxs
@@ -0,0 +1,180 @@
+<?xml version="1.0" encoding="utf-8"?>
+<Wix xmlns="http://schemas.microsoft.com/wix/2006/wi" xmlns:netfx="http://schemas.microsoft.com/wix/NetFxExtension" xmlns:difx="http://schemas.microsoft.com/wix/DifxAppExtension">
+
+
+    <Product Id="{625389D7-EB3C-4d77-A5F6-A285CF99437D}" Name="APM Planner" Language="1033" Version="1.0.0.0" Manufacturer="Michael Oborne" UpgradeCode="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
+        <Package Description="APM Planner Installer" Comments="Apm Planner Installer" Manufacturer="Michael Oborne" InstallerVersion="200" Compressed="yes" />
+
+        <PropertyRef Id="NETFRAMEWORK35" />
+
+        <Condition Message="This application requires .NET Framework 3.5. Please install the .NET Framework then run this installer again."><![CDATA[Installed OR NETFRAMEWORK35]]></Condition>
+
+
+        <Media Id="1" Cabinet="product.cab" EmbedCab="yes" />
+
+        <Directory Id="TARGETDIR" Name="SourceDir">
+            <Directory Id="ProgramFilesFolder" Name="PFiles">
+                <Directory Id="APMPlanner" Name="APM Planner">
+                    <Component Id="InstallDirPermissions" Guid="{525389D7-EB3C-4d77-A5F6-A285CF99437D}" KeyPath="yes"> 
+                        <CreateFolder> 
+                            <Permission User="Everyone" GenericAll="yes" /> 
+                        </CreateFolder>
+                    </Component> 
+                    <Component Id="Planner" Guid="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
+                    
+                        <File Id="gdbinit" Source=".gdbinit" />
+
+                        <File Id="alglibnet2dll" Source="alglibnet2.dll" />
+
+                        <File Id="ArdupilotMegaPlanner.exe" Source="ArdupilotMegaPlanner.exe">
+                            <netfx:NativeImage Id="ngen_ArdupilotMegaPlannerexe"/>
+                        </File>
+                        <File Id="ArdupilotMegaPlannerexeetag" Source="ArdupilotMegaPlanner.exe.etag" />
+                        <File Id="ArdupilotMegaPlannerexeconfig" Source="ArdupilotMegaPlanner.exe.config" />
+
+
+                        <File Id="ArdupilotMegaPlannerpdb" Source="ArdupilotMegaPlanner.pdb" />
+                   
+                        <File Id="block_plane_0dae" Source="block_plane_0.dae" />
+
+                        <File Id="BSEWindowsFormsdll" Source="BSE.Windows.Forms.dll" />
+
+                        <File Id="Coredll" Source="Core.dll" />
+
+                        <File Id="dataflashlogxml" Source="dataflashlog.xml" />
+
+                        <File Id="DirectShowLib2005dll" Source="DirectShowLib-2005.dll" />
+
+                        <File Id="GMapNETCoredll" Source="GMap.NET.Core.dll" />
+
+                        <File Id="GMapNETWindowsFormsdll" Source="GMap.NET.WindowsForms.dll" />
+
+                        <File Id="hudhtml" Source="hud.html" />
+
+                        <File Id="ICSharpCodeSharpZipLibdll" Source="ICSharpCode.SharpZipLib.dll" />
+
+                        <File Id="IonicZipReduceddll" Source="Ionic.Zip.Reduced.dll" />
+
+                        <File Id="IronPythondll" Source="IronPython.dll" />
+
+                        <File Id="IronPythonModulesdll" Source="IronPython.Modules.dll" />
+
+                        <File Id="KMLibdll" Source="KMLib.dll" />
+
+                        <File Id="log4netdll" Source="log4net.dll" />
+
+                        <File Id="mavcmdxml" Source="mavcmd.xml" />
+
+                        <File Id="MAVLinkxml" Source="MAVLink.xml" />
+
+                        <File Id="MetaDataExtractordll" Source="MetaDataExtractor.dll" />
+
+                        <File Id="MicrosoftDirectXDirectInputdll" Source="Microsoft.DirectX.DirectInput.dll" />
+
+                        <File Id="MicrosoftDirectXdll" Source="Microsoft.DirectX.dll" />
+
+                        <File Id="MicrosoftDynamicdll" Source="Microsoft.Dynamic.dll" />
+
+                        <File Id="MicrosoftScriptingCoredll" Source="Microsoft.Scripting.Core.dll" />
+
+                        <File Id="MicrosoftScriptingDebugging.dll" Source="Microsoft.Scripting.Debugging.dll" />
+
+                        <File Id="MicrosoftScriptingdll" Source="Microsoft.Scripting.dll" />
+
+                        <File Id="MicrosoftScriptingExtensionAttribute.dll" Source="Microsoft.Scripting.ExtensionAttribute.dll" />
+
+                        <File Id="netDxfdll" Source="netDxf.dll" />
+
+                        <File Id="OpenTKdll" Source="OpenTK.dll" />
+                        <File Id="OpenTKdllconfig" Source="OpenTK.dll.config" />
+
+
+                        <File Id="OpenTKGLControldll" Source="OpenTK.GLControl.dll" />
+
+                        <File Id="quadhilxml" Source="quadhil.xml" />
+
+                        <File Source="runme" />
+
+
+                        <File Id="SharpKmldll" Source="SharpKml.dll" />
+
+
+                        <File Id="SystemDataSQLitedll" Source="System.Data.SQLite.dll" />
+
+                        <File Id="SystemSpeechdll" Source="System.Speech.dll" />
+
+                        <File Id="Updaterexe" Source="Updater.exe" />
+                        <File Id="Updaterexeconfig" Source="Updater.exe.config" />
+
+
+                        <File Id="ZedGraphdll" Source="ZedGraph.dll" />
+
+                        <File Id="installerwxs" Source="installer.wxs" />
+                        <File Id="installerbat" Source="installer.bat" />
+
+
+                    </Component>
+                    
+                    <Directory Id="drivers" Name="Drivers">
+                        <Component Id="MyDriver" Guid="{6AC8226E-A005-437e-A3CD-0FC32D9A346F}">
+                            <File Id="apm2inf"  Source="Driver\Arduino MEGA 2560.inf" />
+                            <difx:Driver AddRemovePrograms='no' Legacy="yes" PlugAndPlayPrompt="no" />
+                        </Component>
+                    </Directory>
+                </Directory>
+            </Directory>
+
+            <Directory Id="ProgramMenuFolder">
+                <Directory Id="ApplicationProgramsFolder" Name="APM Planner" />
+            </Directory>
+
+        </Directory>
+
+        <DirectoryRef Id="ApplicationProgramsFolder">
+            <Component Id="ApplicationShortcut" Guid="{8BC628BA-08A0-43d6-88C8-D4C007AC4607}">
+                <Shortcut Id="ApplicationStartMenuShortcut" Name="APM Planner" Description="Ardupilot Mega Planner" Target="[APMPlanner]ArdupilotMegaPlanner.exe" WorkingDirectory="APMPlanner" />
+                <RemoveFolder Id="ApplicationProgramsFolder" On="uninstall" />
+
+                <Shortcut Id="UninstallProduct" Name="Uninstall APM Planner" Description="Uninstalls My Application" Target="[System64Folder]msiexec.exe" Arguments="/x [ProductCode]" />
+
+
+
+                <RegistryValue Root="HKCU" Key="Software\MichaelOborne\APMPlanner" Name="installed" Type="integer" Value="1" KeyPath="yes" />
+
+
+
+
+            </Component>
+        </DirectoryRef>
+
+
+        <Feature Id="MyFeature" Title="My 1st Feature" Level="1">
+            <ComponentRef Id="InstallDirPermissions" />
+            <ComponentRef Id="Planner" />
+            <ComponentRef Id="ApplicationShortcut" />
+            <ComponentRef Id="MyDriver" />
+        </Feature>
+
+        
+            <!-- Step 2: Add UI to your installer / Step 4: Trigger the custom action -->
+    <UI>
+        <UIRef Id="WixUI_Minimal" />
+        <Publish Dialog="ExitDialog" 
+            Control="Finish" 
+            Event="DoAction" 
+            Value="LaunchApplication">WIXUI_EXITDIALOGOPTIONALCHECKBOX = 1 and NOT Installed</Publish>
+    </UI>
+    <Property Id="WIXUI_EXITDIALOGOPTIONALCHECKBOXTEXT" Value="Launch APM Planner" />
+
+    <!-- Step 3: Include the custom action -->
+    <Property Id="WixShellExecTarget" Value="[#ArdupilotMegaPlanner.exe]" />
+    <CustomAction Id="LaunchApplication" 
+        BinaryKey="WixCA" 
+        DllEntry="WixShellExec"
+        Impersonate="yes" />
+    </Product>
+
+    
+    
+    
+</Wix>
diff --git a/Tools/ArdupilotMegaPlanner/Msi/wix.exe.config b/Tools/ArdupilotMegaPlanner/Msi/wix.exe.config
new file mode 100644
index 0000000000000000000000000000000000000000..e59af44de2ddb14170137575f1bb09790c6a877c
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Msi/wix.exe.config
@@ -0,0 +1,3 @@
+<?xml version="1.0"?>
+<configuration>
+<startup><supportedRuntime version="v2.0.50727"/></startup></configuration>
diff --git a/Tools/ArdupilotMegaPlanner/Msi/wix.pdb b/Tools/ArdupilotMegaPlanner/Msi/wix.pdb
new file mode 100644
index 0000000000000000000000000000000000000000..8b1508c4126c8a6788dbc38d7c07204d80bda3ce
Binary files /dev/null and b/Tools/ArdupilotMegaPlanner/Msi/wix.pdb differ
diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
index f695ace3a65c85e666f5b1c6b51c3fd51bfeee53..7812b3088e8d6ce36d561f37a34f3eccf0a12e67 100644
--- a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
+++ b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
@@ -33,6 +33,6 @@ using System.Resources;
 // You can specify all the values or you can default the Build and Revision Numbers 
 // by using the '*' as shown below:
 // [assembly: AssemblyVersion("1.0.*")]
-[assembly: AssemblyVersion("1.0.0.0")]
-[assembly: AssemblyFileVersion("1.1.59")]
+[assembly: AssemblyVersion("1.1.*")]
+[assembly: AssemblyFileVersion("1.1.63")]
 [assembly: NeutralResourcesLanguageAttribute("")]
diff --git a/Tools/ArdupilotMegaPlanner/Properties/app.manifest b/Tools/ArdupilotMegaPlanner/Properties/app.manifest
index 177b7df33f9632204e2dad45e9322c4830afc9ae..8df620839827e7727f092f50d4160df7c02653f2 100644
--- a/Tools/ArdupilotMegaPlanner/Properties/app.manifest
+++ b/Tools/ArdupilotMegaPlanner/Properties/app.manifest
@@ -19,8 +19,8 @@
         <requestedExecutionLevel level="asInvoker" uiAccess="false" />
       </requestedPrivileges>
       <applicationRequestMinimum>
-        <PermissionSet class="System.Security.PermissionSet" version="1" Unrestricted="true" ID="Custom" SameSite="site" />
         <defaultAssemblyRequest permissionSetReference="Custom" />
+        <PermissionSet class="System.Security.PermissionSet" version="1" ID="Custom" SameSite="site" Unrestricted="true" />
       </applicationRequestMinimum>
     </security>
   </trustInfo>
diff --git a/Tools/ArdupilotMegaPlanner/RAW_Sensor.cs b/Tools/ArdupilotMegaPlanner/RAW_Sensor.cs
index 04c2427d1bbd5d0f2397581217bfc9def2c050f4..33db53e8f2714db85a148f96b93fa9b26421a426 100644
--- a/Tools/ArdupilotMegaPlanner/RAW_Sensor.cs
+++ b/Tools/ArdupilotMegaPlanner/RAW_Sensor.cs
@@ -217,7 +217,7 @@ namespace ArdupilotMega
 
                     MainV2.cs.ratesensors = 3; // hardcode 3 hz
 
-                    comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RAW_SENSORS, MainV2.cs.ratesensors); // request raw sensor
+                    comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.cs.ratesensors); // request raw sensor
                 }
                 catch { }
             }
@@ -242,12 +242,12 @@ namespace ArdupilotMega
                         //comPort.stopall(true); // ensure off
 
                         Console.WriteLine("Req streams {0} {1}", comPort.bps, DateTime.Now);
-                        //comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTENDED_STATUS, 0); // mode gps raw
-                        //comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_POSITION, 3); // request location
-                        //comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTRA1, 3); // request attitude
-                        //comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTRA2, 3); // request vfr
-                        comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RAW_SENSORS, MainV2.cs.ratesensors); // request raw sensor
-                        //comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RC_CHANNELS, 3); // request rc info
+                        //comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTENDED_STATUS, 0); // mode gps raw
+                        //comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.POSITION, 3); // request location
+                        //comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA1, 3); // request attitude
+                        //comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.EXTRA2, 3); // request vfr
+                        comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.cs.ratesensors); // request raw sensor
+                        //comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RC_CHANNELS, 3); // request rc info
                     }
                     catch
                     {
@@ -260,7 +260,7 @@ namespace ArdupilotMega
         private void CMB_rawupdaterate_SelectedIndexChanged(object sender, EventArgs e)
         {
             MainV2.cs.ratesensors = (byte)int.Parse(CMB_rawupdaterate.Text);
-            comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RAW_SENSORS, (byte)int.Parse(CMB_rawupdaterate.Text)); // request raw sensor
+            comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RAW_SENSORS, (byte)int.Parse(CMB_rawupdaterate.Text)); // request raw sensor
         }
 
         System.IO.StreamWriter sw = null;
diff --git a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs
index 62c057b626442bd1b10d3ea74ef983573ba924ae..c0769e8072f79cd782a53fcbe3e3b6fdcdfdc33b 100644
--- a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs
@@ -55,12 +55,12 @@
             this.RS3 = new System.Windows.Forms.ComboBox();
             this.RS2 = new System.Windows.Forms.ComboBox();
             this.RS1 = new System.Windows.Forms.ComboBox();
+            this.RSSI = new System.Windows.Forms.TextBox();
             this.RS0 = new System.Windows.Forms.TextBox();
             this.label9 = new System.Windows.Forms.Label();
             this.label10 = new System.Windows.Forms.Label();
             this.RTI = new System.Windows.Forms.TextBox();
             this.ATI = new System.Windows.Forms.TextBox();
-            this.RSSI = new System.Windows.Forms.TextBox();
             this.label11 = new System.Windows.Forms.Label();
             this.label12 = new System.Windows.Forms.Label();
             this.BUT_savesettings = new ArdupilotMega.MyButton();
@@ -74,8 +74,7 @@
             // 
             // Progressbar
             // 
-            this.Progressbar.Anchor = ((System.Windows.Forms.AnchorStyles)(((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Left) 
-            | System.Windows.Forms.AnchorStyles.Right)));
+            this.Progressbar.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Left)));
             this.Progressbar.Location = new System.Drawing.Point(12, 402);
             this.Progressbar.Name = "Progressbar";
             this.Progressbar.Size = new System.Drawing.Size(294, 36);
@@ -139,13 +138,16 @@
             // 
             this.S2.FormattingEnabled = true;
             this.S2.Items.AddRange(new object[] {
+            "250",
             "192",
-            "160",
             "128",
             "96",
             "64",
             "32",
-            "16"});
+            "16",
+            "8",
+            "4",
+            "2"});
             this.S2.Location = new System.Drawing.Point(87, 168);
             this.S2.Name = "S2";
             this.S2.Size = new System.Drawing.Size(80, 21);
@@ -283,9 +285,9 @@
             this.label8.AutoSize = true;
             this.label8.Location = new System.Drawing.Point(15, 311);
             this.label8.Name = "label8";
-            this.label8.Size = new System.Drawing.Size(68, 13);
+            this.label8.Size = new System.Drawing.Size(61, 13);
             this.label8.TabIndex = 20;
-            this.label8.Text = "Op Pre Send";
+            this.label8.Text = "Op Resend";
             // 
             // S7
             // 
@@ -395,13 +397,16 @@
             // 
             this.RS2.FormattingEnabled = true;
             this.RS2.Items.AddRange(new object[] {
+            "250",
             "192",
-            "160",
             "128",
             "96",
             "64",
             "32",
-            "16"});
+            "16",
+            "8",
+            "4",
+            "2"});
             this.RS2.Location = new System.Drawing.Point(201, 168);
             this.RS2.Name = "RS2";
             this.RS2.Size = new System.Drawing.Size(80, 21);
@@ -429,6 +434,16 @@
             this.RS1.TabIndex = 22;
             this.toolTip1.SetToolTip(this.RS1, "Serial baud rate in rounded kbps. So 57 means 57600. \r\n");
             // 
+            // RSSI
+            // 
+            this.RSSI.Location = new System.Drawing.Point(87, 51);
+            this.RSSI.Multiline = true;
+            this.RSSI.Name = "RSSI";
+            this.RSSI.ReadOnly = true;
+            this.RSSI.Size = new System.Drawing.Size(194, 58);
+            this.RSSI.TabIndex = 34;
+            this.toolTip1.SetToolTip(this.RSSI, resources.GetString("RSSI.ToolTip"));
+            // 
             // RS0
             // 
             this.RS0.Location = new System.Drawing.Point(201, 115);
@@ -471,16 +486,6 @@
             this.ATI.Size = new System.Drawing.Size(80, 20);
             this.ATI.TabIndex = 32;
             // 
-            // RSSI
-            // 
-            this.RSSI.Location = new System.Drawing.Point(87, 51);
-            this.RSSI.Multiline = true;
-            this.RSSI.Name = "RSSI";
-            this.RSSI.ReadOnly = true;
-            this.RSSI.Size = new System.Drawing.Size(194, 58);
-            this.RSSI.TabIndex = 34;
-            this.toolTip1.SetToolTip(this.RSSI, resources.GetString("RSSI.ToolTip"));
-            // 
             // label11
             // 
             this.label11.AutoSize = true;
@@ -501,6 +506,7 @@
             // 
             // BUT_savesettings
             // 
+            this.BUT_savesettings.Enabled = false;
             this.BUT_savesettings.Location = new System.Drawing.Point(99, 330);
             this.BUT_savesettings.Name = "BUT_savesettings";
             this.BUT_savesettings.Size = new System.Drawing.Size(75, 39);
@@ -521,8 +527,7 @@
             // 
             // lbl_status
             // 
-            this.lbl_status.Anchor = ((System.Windows.Forms.AnchorStyles)(((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Left) 
-            | System.Windows.Forms.AnchorStyles.Right)));
+            this.lbl_status.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Left)));
             this.lbl_status.BackColor = System.Drawing.Color.Transparent;
             this.lbl_status.Location = new System.Drawing.Point(12, 374);
             this.lbl_status.Name = "lbl_status";
@@ -573,7 +578,6 @@
             // 
             this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
             this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
-            this.ClientSize = new System.Drawing.Size(318, 444);
             this.Controls.Add(this.BUT_syncS5);
             this.Controls.Add(this.BUT_syncS3);
             this.Controls.Add(this.BUT_syncS2);
@@ -613,12 +617,9 @@
             this.Controls.Add(this.lbl_status);
             this.Controls.Add(this.Progressbar);
             this.Controls.Add(this.BUT_upload);
-            this.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
-            this.MaximizeBox = false;
-            this.MinimizeBox = false;
             this.MinimumSize = new System.Drawing.Size(334, 482);
             this.Name = "_3DRradio";
-            this.Text = "3DRradio";
+            this.Size = new System.Drawing.Size(334, 482);
             this.ResumeLayout(false);
             this.PerformLayout();
 
diff --git a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.cs b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.cs
index cd1791859a800521115439e054ae53283f6b9f2a..15cd2348204a41767e130703ad2b1db3d5edfe2d 100644
--- a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.cs
+++ b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.cs
@@ -8,10 +8,11 @@ using System.Text;
 using System.Windows.Forms;
 using System.Net;
 using System.IO;
+using ArdupilotMega.Controls.BackstageView;
 
 namespace ArdupilotMega
 {
-    public partial class _3DRradio : Form
+    public partial class _3DRradio : BackStageViewContentPanel
     {
         public delegate void LogEventHandler(string message, int level = 0);
 
@@ -29,9 +30,10 @@ namespace ArdupilotMega
 
         bool getFirmware()
         {
-            //https://raw.github.com/tridge/SiK/master/Firmware/dst/radio.hm_trp.hex
+            // was https://raw.github.com/tridge/SiK/master/Firmware/dst/radio.hm_trp.hex
+            // now http://www.samba.org/tridge/UAV/3DR/radio.hm_trp.hex
 
-            return Common.getFilefromNet("https://raw.github.com/tridge/SiK/master/Firmware/dst/radio.hm_trp.hex", firmwarefile);
+            return Common.getFilefromNet("http://www.samba.org/tridge/UAV/3DR/radio.hm_trp.hex", firmwarefile);
         }
 
         void Sleep(int mstimeout)
@@ -75,7 +77,8 @@ namespace ArdupilotMega
                 uploader_LogEvent("In Bootloader Mode");
                 bootloadermode = true;
             }
-            catch {
+            catch
+            {
                 comPort.Close();
                 comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate;
                 comPort.Open();
@@ -188,13 +191,14 @@ namespace ArdupilotMega
         {
             ArdupilotMega.ICommsSerial comPort = new SerialPort();
 
-            try {
-            comPort.PortName = MainV2.comPort.BaseStream.PortName;
-            comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate;
+            try
+            {
+                comPort.PortName = MainV2.comPort.BaseStream.PortName;
+                comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate;
 
-            comPort.ReadTimeout = 4000;
+                comPort.ReadTimeout = 4000;
 
-            comPort.Open();
+                comPort.Open();
 
 
             }
@@ -447,6 +451,9 @@ namespace ArdupilotMega
                         {
                             Control[] controls = this.Controls.Find("R" + values[0].Trim(), false);
 
+                            if (controls.Length == 0)
+                                continue;
+
                             if (controls[0].GetType() == typeof(CheckBox))
                             {
                                 ((CheckBox)controls[0]).Checked = values[2].Trim() == "1";
@@ -483,6 +490,8 @@ namespace ArdupilotMega
             }
 
             comPort.Close();
+
+            BUT_savesettings.Enabled = true;
         }
 
         string Serial_ReadLine(ArdupilotMega.ICommsSerial comPort)
@@ -547,7 +556,7 @@ namespace ArdupilotMega
                 }
             }
 
-            Console.WriteLine("responce " + level + " " + ans.Replace('\0',' '));
+            Console.WriteLine("responce " + level + " " + ans.Replace('\0', ' '));
 
             // try again
             if (ans == "" && level == 0)
@@ -571,7 +580,7 @@ namespace ArdupilotMega
             // check for config responce "OK"
             Console.WriteLine("Connect btr " + comPort.BytesToRead + " baud " + comPort.BaudRate);
             string conn = comPort.ReadExisting();
-            Console.WriteLine("Connect first responce " + conn.Replace('\0',' ') + " " + conn.Length);
+            Console.WriteLine("Connect first responce " + conn.Replace('\0', ' ') + " " + conn.Length);
             if (conn.Contains("OK"))
             {
                 //return true;
diff --git a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx
index 5194d642e64028700df19f224c8f3384d361dbbc..2e8ee646bd5e3d2241c2aed997777756a01d4502 100644
--- a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx
+++ b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx
@@ -161,83 +161,6 @@ stx: number of serial transmit overflows
 rrx: number of serial receive overflows 
 ecc: number of 12 bit words successfully corrected by the golay code
 which result in a valid packet CRC 
-</value>
-  </data>
-  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
-  <data name="$this.Icon" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
-    <value>
-        AAABAAEAICAAAAEAIACoEAAAFgAAACgAAAAgAAAAQAAAAAEAIAAAAAAAABAAABILAAASCwAAAAAAAAAA
-        AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADOxkjAtnoOAKpJ4vyiK
-        c+8nh3D/J4Zv/yeHcP8oi3PvKpJ4vy6fg4AzsZIwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
-        AAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADjGo2AyspPfLZ+D/yiQ
-        d/8hlXj/G6F9/xeqg/8XqYL/GKqD/xuhfv8ilnn/KZB3/y2fhP8yspPfN8ajYAAAAAAAAAAAAAAAAAAA
-        AAAAAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADvRrDA1vpzfL6uN/yel
-        hP8XvJD/DMyY/wfQl/8FzJP/A8qS/wPJkf8EypL/BsyU/wnRmP8PzZn/Gb2R/yemhP8tqoz/Mb2a3zbQ
-        qkAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAA4y6ZgMbWV/yin
-        iP8WwZP/Btqf/wDPlf8AyI7/A8aP/yfNnv9T2LP/UNax/03XsP8506b/G8ya/wHKkf8F0Zf/CNuf/xLB
-        kv8fpYT/J7KQ/y7IomAAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAANcajny+w
-        kf8hqoj/CNSd/wDRlf8Axor/Hcyd/3Lhwf+p7Nj/o+vV/57m0/+X5dD/k+TN/4/jzf+K5Mz/fuHH/0PW
-        rf8HzJT/ANCT/wDRlv8OpX//HayI/yrFn58AAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAADDC
-        nmAtro7/H62J/wPWmv8Ay47/AMaO/3XhxP+e6tT/mObP/5Pjy/+Q4sr/jODJ/4ffx/+C3MT/f9vC/3nb
-        wf9y2r7/adq7/2DauP8ZzZv/Fdae/8T/9/9WxKj/HKuI/y7IomAAAAAAAAAAAAAAAAD///8AAAAAAAAA
-        AAAiuZMwKKyM/x6ohf8C1Zr/AMmL/wHGjv+49OL///////////9+3ML/f9zD/4Dcwv9+28L/e9rA/3bZ
-        vv9w1rr/Z9S4/17Rs/9Qz63/Qcyn/3LewP////////////n///8MpH7/JbKP/zXQqUAAAAAAAAAAAP//
-        /wAAAAAAAAAAABymhN8dnn//BNGa/wDKjP8AxY3/sfHf/////////////////2nXt/9w1rv/c9e8/3TX
-        vP9x17z/a9W5/2TTtf9Y0K//SMyp/zXFoP9i07X/////////////////f/LR/wDQlf8epYT/Mb2a3wAA
-        AAAAAAAA////AAAAAAADlnJgFZR1/wq4iv8AzpH/AMCD/4rmzf//////////////////////WdGv/2PU
-        tf9p1rf/atS4/2nUtv9i0rT/Vc+u/0fKpv8zxZz/Ws+w//////////////////////8GyJL/ANCS/xLB
-        kv8tq4z/OMajYAAAAAD///8AAAAAAACHZt8NkW//ANKV/wDChP9i27r//////////////////////9Dx
-        6P9MzKn/Vc+v/17Rsv9g0rP/XNCx/1XNrv9Fyaf/McSd/1fPr///////////////////////QM2m/ynK
-        oP8JzJX/C9yh/ymmhf80spPfAAAAAP///wAAcUwwAHtc/wCrfP8AyIv/AMKK////////////////////
-        /////////////5Dgyv9Gyqb/TMyq/07Nq/9MzKn/Qcmj/y/Fnf9Wzq3//////////////////////57k
-        0v8av5T/Lceg/yzOo/8M05v/Hr6T/zCghf80spIw////AABoRYAAclT/AL2H/wDBhf9R1rL/////////
-        ////////4vfw//////////////////H8+P9KzKn/Ocah/zTFnv8qwpj/Us2t////////////////////
-        ////////DLqM/yDBlv8wxp//OM6m/xPPm/8Xz53/LZF5/y+fg4////8AAGNAvwB7Wf8Aw4j/ALyC/4bj
-        yP+g5tL/g93E/2HSsv9Pzqz/Us6s//////////////////////9Yzq//Gr2S/0jLp///////////////
-        /////////////yrDm/8SvI//JMGY/zDHn/81zKT/Is2e/xTUnf8nl3v/LJJ5v////wAAXz3vAIlg/wDA
-        hf8AuoD/quzZ/5Hjyv9628D/ada2/1jRsP9Jy6f/a9a4//////////////////////+Y4s7/////////
-        //////////////////+c4tD/AbaH/xW8kf8jwZj/LcWd/y/Jn/8kzJ3/E9Ca/yGjgf8ri3Tv////AABd
-        PP8Ak2b/AL6D/w/Ekv+m6tf/j+HJ/3vawP9p1rf/W9Gx/0rNqf85yJ//Nsaf////////////////////
-        /////////////////////////////wCwe/8AtoT/ELqP/xu+k/8jwZj/KMeb/yHKm/8QzZf/HqyG/ymI
-        cf////8AAF07/wCSZP8AvYL/GMWU/6Dn1P+K38f/ddi+/27Wuf+E3MX/leHN/6fm1f+l5tX/neLQ////
-        ////////////////////////////////////////j9/J/27Vuv9Tzq7/JsKY/xa/kv8aw5T/FcaW/wvL
-        lf8aqoT/J4dw/////wAAXTv/AJFk/wC9gP8GwY3/mObQ/5rkz/+26dv/y/Hl/8Dt3/+06tz/pebV/5bg
-        zP+g5NL//////////////v///f7+//7+/v//////7fn2////////////tOnb/6Ll0v+v6Nj/jeDI/zXK
-        o/8IxJD/BMqS/xaqgv8lh2//////AABeO+8AgVf/AL1//wDBif/R9uv/1PPq/8Tv5P+36t3/rujY/6Lk
-        0v+U4cv/jt7J//j8+///////+/38//f8+//2+/r/+Pz7//3+/v/m9/P/9Pv6//D6+P9/28L/jd7J/5jj
-        z/+h5dL/qOvX/4Hmyf8f1J//E596/yOJcO////8AAGA8vwB3U/8p06P/hufM/8Ty5f/D7+T/s+vb/6bm
-        1P+c4c//j9/K/4vcyP/t+fb///7///j8/P/0+/r/8vr5//P7+f/1+/r/+/39///////i9fL/ZNO1/3HW
-        vP992sH/htzG/4vhyv+S5dD/mO7W/6X74v80noT/Io90v////wAAZkCAAHla/33ny/945cb/nunV/7Xr
-        3v+l5tT/luDN/4ndxv992cL/1vLq//v9/P/1+/n/8vv4//L69//z+/j/9Pv5/7Xo2//x+vn/////////
-        //+y59n/aNS3/3LWvP932r//fNzD/4Ljyf+J7ND/l/bd/yORdf8knH6A////AABuRzAAdlT/Xc6x/23o
-        xv9s4MH/qurZ/5jiz/+I3cb/edjA/8ju5f/3/Pv/8vv4//H6+P/y+/j/6/f0/7np3v/7/fz//v7+/6fk
-        1f+56tz///////////9h0bT/aNW4/23Wu/9v3L//dOLG/37w0f9m1rn/Hpt8/ymujTD///8AAAAAAACD
-        X98po4X/Z+7K/1vgvP+A4sf/jOHK/3rZwv+r59f/9Pv6/+/69//v+vf/8vr4/9fy6/9n0rf/VM6t/6Di
-        0v/N7+f/adO4/1PMrf9t1Lr/i9zI/1/Rs/9h0rX/ZNe4/2bbvf9s5sb/ePfV/z2ylf8lrozfAAAAAP//
-        /wAAAAAAAJNsYAWQbf9U1rP/Vee//0rYsf993sb/pebV//P7+v/s+Pb/6/f1/+749v+s5tj/Vc2u/1jP
-        r/9ZzrD/btW5/1bOr/9Wza//Vs6v/1fOr/9Z0LD/WdCy/1vTtP9d1rX/Xt+8/2btyP9k4L//IaaF/y7D
-        nmAAAAAA////AAAAAAAAAAAAD6J9zyCjgv9S68L/P9+0/2Pevv/5////7/v6/+v59//j9/L/gtvF/1PN
-        r/9Wz7D/Wc+x/1nQsf9Zz7H/WM6w/1fPsP9UzrD/VM+w/1TPrv9U0a//U9Oy/1Tatv9Z5sD/Y/LL/zSx
-        lP8qupbPAAAAAAAAAAD///8AAAAAAAAAAAAYto4wGaeE/y23lP8+5rn/6/////j////w//3/ve/i/2bV
-        uP9Tzq7/Vc+v/1jPsP9Z0LL/WM+w/1fOsf9Wz7D/Us2w/1HOrf9Qzq3/T9Cu/0zSr/9M2LP/TeC5/1bt
-        xP9HxaX/KLKQ/zTPqDAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAkvpdgG6iF/y++m//e/////P///3rl
-        yf9G0K3/VdKy/1bPsf9Wz7H/Vs6w/1bPsP9Sza//Ucyu/0/Nrf9NzKz/S82s/0fOrP9G0a7/QdWv/0Le
-        tP9I6L7/Q8Ok/yitjP8yyKJgAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAmwJlgG6iF/yK3
-        kP8k3q7/H9el/x7Pn/8tzKT/Q9Cs/1HQsP9Q0K7/TM6u/0nMrf9Hzaz/RMyp/0LNqf8+zqn/ONGo/zTV
-        qf833rD/O+S4/zvCof8orIv/MMSfYAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAA
-        AAAkvpdgG6iE/xukgv8gy53/HNql/xzRn/8czJz/HcmZ/yXJnP8qyp7/Lcqg/yzLn/8nypz/JMqc/yTO
-        n/8l1KT/KN2r/y3Tpv8nq4n/JaqJ/yzAm2AAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAA
-        AAAAAAAAAAAAAAAAAAAato8wFKN/zxCScv8RnHn/DbqM/wjIlP8GyZT/BsaS/wbFkf8GxZH/B8WR/wfH
-        k/8IypX/DMmV/xG3jP8WoX3/Fph2/xqkgs8ft5EwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA////AAAA
-        AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJVvYACGZM8Aelr/AHlZ/wCFX/8AiWL/AJlr/wCb
-        bP8AlGf/AI5k/wB/W/8AeFj/AHtb/wCHZd8ClXBgAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
-        AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAABwSzAAaESAAGI/vwBf
-        Pd8AXTz/AF08/wBdPP8AXz3fAGJAvwBoRIAAcUswAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
-        AAAAAAAAAAAAAP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
-        /wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
-        /wD///8A////AP///wD///8A/+AD//+AAP/+AAA//AAAH/gAAA/wAAAH4AAAA+AAAAPAAAABwAAAAYAA
-        AACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAwAAAAcAAAAHgAAAD4AAAA/AA
-        AAf4AAAP/AAAH/4AAD//gAD//+AD//////8=
 </value>
   </data>
 </root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Script.cs b/Tools/ArdupilotMegaPlanner/Script.cs
index 60d5ea4fa15e7e763e0ffb93fc719d2221aed2d6..9face19c31ad1b230d46b041793f0175aaca0032 100644
--- a/Tools/ArdupilotMegaPlanner/Script.cs
+++ b/Tools/ArdupilotMegaPlanner/Script.cs
@@ -14,7 +14,7 @@ namespace ArdupilotMega
         static Microsoft.Scripting.Hosting.ScriptScope scope;
 
         // keeps history
-        MAVLink.__mavlink_rc_channels_override_t rc = new MAVLink.__mavlink_rc_channels_override_t();
+        MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t();
 
         public Script()
         {
diff --git a/Tools/ArdupilotMegaPlanner/SerialInput.cs b/Tools/ArdupilotMegaPlanner/SerialInput.cs
index 5a1d5542e3c06c4f5110af232701e86661af70b7..948257f7c12c0fb6cea9765630e8c2cda0b566ef 100644
--- a/Tools/ArdupilotMegaPlanner/SerialInput.cs
+++ b/Tools/ArdupilotMegaPlanner/SerialInput.cs
@@ -159,7 +159,7 @@ namespace ArdupilotMega
                             {
                                 MainV2.giveComport = true;
 
-                                MainV2.comPort.setWP(gotohere, 0, MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT, (byte)2);
+                                MainV2.comPort.setWP(gotohere, 0, MAVLink.MAV_FRAME.GLOBAL_RELATIVE_ALT, (byte)2);
 
                                 GCSViews.FlightData.GuidedModeWP = new PointLatLngAlt(gotohere);
 
diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.cs b/Tools/ArdupilotMegaPlanner/Setup/Setup.cs
index 1bb21aee79f01b8b657f5be49c16ee146c3cf717..348c1cd0ce2c15259607ab484c8fb6a71900eb72 100644
--- a/Tools/ArdupilotMegaPlanner/Setup/Setup.cs
+++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.cs
@@ -1719,8 +1719,7 @@ namespace ArdupilotMega.Setup
 #else
                 MainV2.comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_CALIBRATE_ACC);
 #endif
-
-                BUT_levelac2.Text = "Complete";
+                BUT_levelplane.Text = "Complete";
             }
             catch
             {
diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.resx b/Tools/ArdupilotMegaPlanner/Setup/Setup.resx
index 0524d1cf2e7ea21806da0bbed07673661554e6f3..078647e4e005dc58182dc30a079a33987846e720 100644
--- a/Tools/ArdupilotMegaPlanner/Setup/Setup.resx
+++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.resx
@@ -117,1656 +117,15 @@
   <resheader name="writer">
     <value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
   </resheader>
-  <data name="&gt;&gt;groupBoxElevons.Name" xml:space="preserve">
-    <value>groupBoxElevons</value>
-  </data>
-  <data name="&gt;&gt;groupBoxElevons.Type" xml:space="preserve">
-    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;groupBoxElevons.Parent" xml:space="preserve">
-    <value>tabRadioIn</value>
-  </data>
-  <data name="&gt;&gt;groupBoxElevons.ZOrder" xml:space="preserve">
-    <value>0</value>
-  </data>
-  <data name="&gt;&gt;CHK_revch3.Name" xml:space="preserve">
-    <value>CHK_revch3</value>
-  </data>
-  <data name="&gt;&gt;CHK_revch3.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CHK_revch3.Parent" xml:space="preserve">
-    <value>tabRadioIn</value>
-  </data>
-  <data name="&gt;&gt;CHK_revch3.ZOrder" xml:space="preserve">
-    <value>1</value>
-  </data>
-  <data name="&gt;&gt;CHK_revch4.Name" xml:space="preserve">
-    <value>CHK_revch4</value>
-  </data>
-  <data name="&gt;&gt;CHK_revch4.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CHK_revch4.Parent" xml:space="preserve">
-    <value>tabRadioIn</value>
-  </data>
-  <data name="&gt;&gt;CHK_revch4.ZOrder" xml:space="preserve">
-    <value>2</value>
-  </data>
-  <data name="&gt;&gt;CHK_revch2.Name" xml:space="preserve">
-    <value>CHK_revch2</value>
-  </data>
-  <data name="&gt;&gt;CHK_revch2.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CHK_revch2.Parent" xml:space="preserve">
-    <value>tabRadioIn</value>
-  </data>
-  <data name="&gt;&gt;CHK_revch2.ZOrder" xml:space="preserve">
-    <value>3</value>
-  </data>
-  <data name="&gt;&gt;CHK_revch1.Name" xml:space="preserve">
-    <value>CHK_revch1</value>
-  </data>
-  <data name="&gt;&gt;CHK_revch1.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CHK_revch1.Parent" xml:space="preserve">
-    <value>tabRadioIn</value>
-  </data>
-  <data name="&gt;&gt;CHK_revch1.ZOrder" xml:space="preserve">
-    <value>4</value>
-  </data>
-  <data name="&gt;&gt;BUT_Calibrateradio.Name" xml:space="preserve">
-    <value>BUT_Calibrateradio</value>
-  </data>
-  <data name="&gt;&gt;BUT_Calibrateradio.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;BUT_Calibrateradio.Parent" xml:space="preserve">
-    <value>tabRadioIn</value>
-  </data>
-  <data name="&gt;&gt;BUT_Calibrateradio.ZOrder" xml:space="preserve">
-    <value>5</value>
-  </data>
-  <data name="&gt;&gt;BAR8.Name" xml:space="preserve">
-    <value>BAR8</value>
-  </data>
-  <data name="&gt;&gt;BAR8.Type" xml:space="preserve">
-    <value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;BAR8.Parent" xml:space="preserve">
-    <value>tabRadioIn</value>
-  </data>
-  <data name="&gt;&gt;BAR8.ZOrder" xml:space="preserve">
-    <value>6</value>
-  </data>
-  <data name="&gt;&gt;BAR7.Name" xml:space="preserve">
-    <value>BAR7</value>
-  </data>
-  <data name="&gt;&gt;BAR7.Type" xml:space="preserve">
-    <value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;BAR7.Parent" xml:space="preserve">
-    <value>tabRadioIn</value>
-  </data>
-  <data name="&gt;&gt;BAR7.ZOrder" xml:space="preserve">
-    <value>7</value>
-  </data>
-  <data name="&gt;&gt;BAR6.Name" xml:space="preserve">
-    <value>BAR6</value>
-  </data>
-  <data name="&gt;&gt;BAR6.Type" xml:space="preserve">
-    <value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;BAR6.Parent" xml:space="preserve">
-    <value>tabRadioIn</value>
-  </data>
-  <data name="&gt;&gt;BAR6.ZOrder" xml:space="preserve">
-    <value>8</value>
-  </data>
-  <data name="&gt;&gt;BAR5.Name" xml:space="preserve">
-    <value>BAR5</value>
-  </data>
-  <data name="&gt;&gt;BAR5.Type" xml:space="preserve">
-    <value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;BAR5.Parent" xml:space="preserve">
-    <value>tabRadioIn</value>
-  </data>
-  <data name="&gt;&gt;BAR5.ZOrder" xml:space="preserve">
-    <value>9</value>
-  </data>
-  <data name="&gt;&gt;BARpitch.Name" xml:space="preserve">
-    <value>BARpitch</value>
-  </data>
-  <data name="&gt;&gt;BARpitch.Type" xml:space="preserve">
-    <value>ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;BARpitch.Parent" xml:space="preserve">
-    <value>tabRadioIn</value>
-  </data>
-  <data name="&gt;&gt;BARpitch.ZOrder" xml:space="preserve">
-    <value>10</value>
-  </data>
-  <data name="&gt;&gt;BARthrottle.Name" xml:space="preserve">
-    <value>BARthrottle</value>
-  </data>
-  <data name="&gt;&gt;BARthrottle.Type" xml:space="preserve">
-    <value>ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;BARthrottle.Parent" xml:space="preserve">
-    <value>tabRadioIn</value>
-  </data>
-  <data name="&gt;&gt;BARthrottle.ZOrder" xml:space="preserve">
-    <value>11</value>
-  </data>
-  <data name="&gt;&gt;BARyaw.Name" xml:space="preserve">
-    <value>BARyaw</value>
-  </data>
-  <data name="&gt;&gt;BARyaw.Type" xml:space="preserve">
-    <value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;BARyaw.Parent" xml:space="preserve">
-    <value>tabRadioIn</value>
-  </data>
-  <data name="&gt;&gt;BARyaw.ZOrder" xml:space="preserve">
-    <value>12</value>
-  </data>
-  <data name="&gt;&gt;BARroll.Name" xml:space="preserve">
-    <value>BARroll</value>
-  </data>
-  <data name="&gt;&gt;BARroll.Type" xml:space="preserve">
-    <value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;BARroll.Parent" xml:space="preserve">
-    <value>tabRadioIn</value>
-  </data>
-  <data name="&gt;&gt;BARroll.ZOrder" xml:space="preserve">
-    <value>13</value>
-  </data>
-  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
-  <data name="tabRadioIn.Location" type="System.Drawing.Point, System.Drawing">
-    <value>4, 22</value>
-  </data>
-  <assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
-  <data name="tabRadioIn.Padding" type="System.Windows.Forms.Padding, System.Windows.Forms">
-    <value>3, 3, 3, 3</value>
-  </data>
-  <data name="tabRadioIn.Size" type="System.Drawing.Size, System.Drawing">
-    <value>666, 393</value>
-  </data>
-  <assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
-  <data name="tabRadioIn.TabIndex" type="System.Int32, mscorlib">
-    <value>0</value>
-  </data>
-  <data name="tabRadioIn.Text" xml:space="preserve">
-    <value>Radio Input</value>
-  </data>
-  <data name="&gt;&gt;tabRadioIn.Name" xml:space="preserve">
-    <value>tabRadioIn</value>
-  </data>
-  <data name="&gt;&gt;tabRadioIn.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;tabRadioIn.Parent" xml:space="preserve">
-    <value>Tabs</value>
-  </data>
-  <data name="&gt;&gt;tabRadioIn.ZOrder" xml:space="preserve">
-    <value>0</value>
-  </data>
-  <data name="&gt;&gt;CB_simple6.Name" xml:space="preserve">
-    <value>CB_simple6</value>
-  </data>
-  <data name="&gt;&gt;CB_simple6.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CB_simple6.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;CB_simple6.ZOrder" xml:space="preserve">
-    <value>0</value>
-  </data>
-  <data name="&gt;&gt;CB_simple5.Name" xml:space="preserve">
-    <value>CB_simple5</value>
-  </data>
-  <data name="&gt;&gt;CB_simple5.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CB_simple5.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;CB_simple5.ZOrder" xml:space="preserve">
-    <value>1</value>
-  </data>
-  <data name="&gt;&gt;CB_simple4.Name" xml:space="preserve">
-    <value>CB_simple4</value>
-  </data>
-  <data name="&gt;&gt;CB_simple4.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CB_simple4.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;CB_simple4.ZOrder" xml:space="preserve">
-    <value>2</value>
-  </data>
-  <data name="&gt;&gt;CB_simple3.Name" xml:space="preserve">
-    <value>CB_simple3</value>
-  </data>
-  <data name="&gt;&gt;CB_simple3.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CB_simple3.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;CB_simple3.ZOrder" xml:space="preserve">
-    <value>3</value>
-  </data>
-  <data name="&gt;&gt;CB_simple2.Name" xml:space="preserve">
-    <value>CB_simple2</value>
-  </data>
-  <data name="&gt;&gt;CB_simple2.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CB_simple2.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;CB_simple2.ZOrder" xml:space="preserve">
-    <value>4</value>
-  </data>
-  <data name="&gt;&gt;CB_simple1.Name" xml:space="preserve">
-    <value>CB_simple1</value>
-  </data>
-  <data name="&gt;&gt;CB_simple1.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CB_simple1.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;CB_simple1.ZOrder" xml:space="preserve">
-    <value>5</value>
-  </data>
-  <data name="&gt;&gt;label14.Name" xml:space="preserve">
-    <value>label14</value>
-  </data>
-  <data name="&gt;&gt;label14.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label14.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;label14.ZOrder" xml:space="preserve">
-    <value>6</value>
-  </data>
-  <data name="&gt;&gt;LBL_flightmodepwm.Name" xml:space="preserve">
-    <value>LBL_flightmodepwm</value>
-  </data>
-  <data name="&gt;&gt;LBL_flightmodepwm.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;LBL_flightmodepwm.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;LBL_flightmodepwm.ZOrder" xml:space="preserve">
-    <value>7</value>
-  </data>
-  <data name="&gt;&gt;label13.Name" xml:space="preserve">
-    <value>label13</value>
-  </data>
-  <data name="&gt;&gt;label13.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label13.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;label13.ZOrder" xml:space="preserve">
-    <value>8</value>
-  </data>
-  <data name="&gt;&gt;lbl_currentmode.Name" xml:space="preserve">
-    <value>lbl_currentmode</value>
-  </data>
-  <data name="&gt;&gt;lbl_currentmode.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;lbl_currentmode.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;lbl_currentmode.ZOrder" xml:space="preserve">
-    <value>9</value>
-  </data>
-  <data name="&gt;&gt;label12.Name" xml:space="preserve">
-    <value>label12</value>
-  </data>
-  <data name="&gt;&gt;label12.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label12.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;label12.ZOrder" xml:space="preserve">
-    <value>10</value>
-  </data>
-  <data name="&gt;&gt;label11.Name" xml:space="preserve">
-    <value>label11</value>
-  </data>
-  <data name="&gt;&gt;label11.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label11.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;label11.ZOrder" xml:space="preserve">
-    <value>11</value>
-  </data>
-  <data name="&gt;&gt;label10.Name" xml:space="preserve">
-    <value>label10</value>
-  </data>
-  <data name="&gt;&gt;label10.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label10.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;label10.ZOrder" xml:space="preserve">
-    <value>12</value>
-  </data>
-  <data name="&gt;&gt;label9.Name" xml:space="preserve">
-    <value>label9</value>
-  </data>
-  <data name="&gt;&gt;label9.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label9.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;label9.ZOrder" xml:space="preserve">
-    <value>13</value>
-  </data>
-  <data name="&gt;&gt;label8.Name" xml:space="preserve">
-    <value>label8</value>
-  </data>
-  <data name="&gt;&gt;label8.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label8.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;label8.ZOrder" xml:space="preserve">
-    <value>14</value>
-  </data>
-  <data name="&gt;&gt;label7.Name" xml:space="preserve">
-    <value>label7</value>
-  </data>
-  <data name="&gt;&gt;label7.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label7.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;label7.ZOrder" xml:space="preserve">
-    <value>15</value>
-  </data>
-  <data name="&gt;&gt;label6.Name" xml:space="preserve">
-    <value>label6</value>
-  </data>
-  <data name="&gt;&gt;label6.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label6.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;label6.ZOrder" xml:space="preserve">
-    <value>16</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode6.Name" xml:space="preserve">
-    <value>CMB_fmode6</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode6.Type" xml:space="preserve">
-    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode6.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode6.ZOrder" xml:space="preserve">
-    <value>17</value>
-  </data>
-  <data name="&gt;&gt;label5.Name" xml:space="preserve">
-    <value>label5</value>
-  </data>
-  <data name="&gt;&gt;label5.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label5.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;label5.ZOrder" xml:space="preserve">
-    <value>18</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode5.Name" xml:space="preserve">
-    <value>CMB_fmode5</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode5.Type" xml:space="preserve">
-    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode5.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode5.ZOrder" xml:space="preserve">
-    <value>19</value>
-  </data>
-  <data name="&gt;&gt;label4.Name" xml:space="preserve">
-    <value>label4</value>
-  </data>
-  <data name="&gt;&gt;label4.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label4.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;label4.ZOrder" xml:space="preserve">
-    <value>20</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode4.Name" xml:space="preserve">
-    <value>CMB_fmode4</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode4.Type" xml:space="preserve">
-    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode4.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode4.ZOrder" xml:space="preserve">
-    <value>21</value>
-  </data>
-  <data name="&gt;&gt;label3.Name" xml:space="preserve">
-    <value>label3</value>
-  </data>
-  <data name="&gt;&gt;label3.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label3.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;label3.ZOrder" xml:space="preserve">
-    <value>22</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode3.Name" xml:space="preserve">
-    <value>CMB_fmode3</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode3.Type" xml:space="preserve">
-    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode3.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode3.ZOrder" xml:space="preserve">
-    <value>23</value>
-  </data>
-  <data name="&gt;&gt;label2.Name" xml:space="preserve">
-    <value>label2</value>
-  </data>
-  <data name="&gt;&gt;label2.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label2.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;label2.ZOrder" xml:space="preserve">
-    <value>24</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode2.Name" xml:space="preserve">
-    <value>CMB_fmode2</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode2.Type" xml:space="preserve">
-    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode2.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode2.ZOrder" xml:space="preserve">
-    <value>25</value>
-  </data>
-  <data name="&gt;&gt;label1.Name" xml:space="preserve">
-    <value>label1</value>
-  </data>
-  <data name="&gt;&gt;label1.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label1.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;label1.ZOrder" xml:space="preserve">
-    <value>26</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode1.Name" xml:space="preserve">
-    <value>CMB_fmode1</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode1.Type" xml:space="preserve">
-    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode1.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;CMB_fmode1.ZOrder" xml:space="preserve">
-    <value>27</value>
-  </data>
-  <data name="&gt;&gt;BUT_SaveModes.Name" xml:space="preserve">
-    <value>BUT_SaveModes</value>
-  </data>
-  <data name="&gt;&gt;BUT_SaveModes.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;BUT_SaveModes.Parent" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;BUT_SaveModes.ZOrder" xml:space="preserve">
-    <value>28</value>
-  </data>
-  <data name="tabModes.Location" type="System.Drawing.Point, System.Drawing">
-    <value>4, 22</value>
-  </data>
-  <data name="tabModes.Size" type="System.Drawing.Size, System.Drawing">
-    <value>666, 393</value>
-  </data>
-  <data name="tabModes.TabIndex" type="System.Int32, mscorlib">
-    <value>3</value>
-  </data>
-  <data name="tabModes.Text" xml:space="preserve">
-    <value>Modes</value>
-  </data>
-  <data name="&gt;&gt;tabModes.Name" xml:space="preserve">
-    <value>tabModes</value>
-  </data>
-  <data name="&gt;&gt;tabModes.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;tabModes.Parent" xml:space="preserve">
-    <value>Tabs</value>
-  </data>
-  <data name="&gt;&gt;tabModes.ZOrder" xml:space="preserve">
-    <value>1</value>
-  </data>
-  <data name="&gt;&gt;BUT_MagCalibration.Name" xml:space="preserve">
-    <value>BUT_MagCalibration</value>
-  </data>
-  <data name="&gt;&gt;BUT_MagCalibration.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;BUT_MagCalibration.Parent" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;BUT_MagCalibration.ZOrder" xml:space="preserve">
-    <value>0</value>
-  </data>
-  <data name="&gt;&gt;label27.Name" xml:space="preserve">
-    <value>label27</value>
-  </data>
-  <data name="&gt;&gt;label27.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label27.Parent" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;label27.ZOrder" xml:space="preserve">
-    <value>1</value>
-  </data>
-  <data name="&gt;&gt;CMB_sonartype.Name" xml:space="preserve">
-    <value>CMB_sonartype</value>
-  </data>
-  <data name="&gt;&gt;CMB_sonartype.Type" xml:space="preserve">
-    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CMB_sonartype.Parent" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;CMB_sonartype.ZOrder" xml:space="preserve">
-    <value>2</value>
-  </data>
-  <data name="&gt;&gt;CHK_enableoptflow.Name" xml:space="preserve">
-    <value>CHK_enableoptflow</value>
-  </data>
-  <data name="&gt;&gt;CHK_enableoptflow.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CHK_enableoptflow.Parent" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;CHK_enableoptflow.ZOrder" xml:space="preserve">
-    <value>3</value>
-  </data>
-  <data name="&gt;&gt;pictureBox2.Name" xml:space="preserve">
-    <value>pictureBox2</value>
-  </data>
-  <data name="&gt;&gt;pictureBox2.Type" xml:space="preserve">
-    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;pictureBox2.Parent" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;pictureBox2.ZOrder" xml:space="preserve">
-    <value>4</value>
-  </data>
-  <data name="&gt;&gt;linkLabelmagdec.Name" xml:space="preserve">
-    <value>linkLabelmagdec</value>
-  </data>
-  <data name="&gt;&gt;linkLabelmagdec.Type" xml:space="preserve">
-    <value>System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;linkLabelmagdec.Parent" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;linkLabelmagdec.ZOrder" xml:space="preserve">
-    <value>5</value>
-  </data>
-  <data name="&gt;&gt;label100.Name" xml:space="preserve">
-    <value>label100</value>
-  </data>
-  <data name="&gt;&gt;label100.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label100.Parent" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;label100.ZOrder" xml:space="preserve">
-    <value>6</value>
-  </data>
-  <data name="&gt;&gt;TXT_declination.Name" xml:space="preserve">
-    <value>TXT_declination</value>
-  </data>
-  <data name="&gt;&gt;TXT_declination.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;TXT_declination.Parent" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;TXT_declination.ZOrder" xml:space="preserve">
-    <value>7</value>
-  </data>
-  <data name="&gt;&gt;CHK_enableairspeed.Name" xml:space="preserve">
-    <value>CHK_enableairspeed</value>
-  </data>
-  <data name="&gt;&gt;CHK_enableairspeed.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CHK_enableairspeed.Parent" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;CHK_enableairspeed.ZOrder" xml:space="preserve">
-    <value>8</value>
-  </data>
-  <data name="&gt;&gt;CHK_enablesonar.Name" xml:space="preserve">
-    <value>CHK_enablesonar</value>
-  </data>
-  <data name="&gt;&gt;CHK_enablesonar.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CHK_enablesonar.Parent" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;CHK_enablesonar.ZOrder" xml:space="preserve">
-    <value>9</value>
-  </data>
-  <data name="&gt;&gt;CHK_enablecompass.Name" xml:space="preserve">
-    <value>CHK_enablecompass</value>
-  </data>
-  <data name="&gt;&gt;CHK_enablecompass.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CHK_enablecompass.Parent" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;CHK_enablecompass.ZOrder" xml:space="preserve">
-    <value>10</value>
-  </data>
-  <data name="&gt;&gt;pictureBox4.Name" xml:space="preserve">
-    <value>pictureBox4</value>
-  </data>
-  <data name="&gt;&gt;pictureBox4.Type" xml:space="preserve">
-    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;pictureBox4.Parent" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;pictureBox4.ZOrder" xml:space="preserve">
-    <value>11</value>
-  </data>
-  <data name="&gt;&gt;pictureBox3.Name" xml:space="preserve">
-    <value>pictureBox3</value>
-  </data>
-  <data name="&gt;&gt;pictureBox3.Type" xml:space="preserve">
-    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;pictureBox3.Parent" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;pictureBox3.ZOrder" xml:space="preserve">
-    <value>12</value>
-  </data>
-  <data name="&gt;&gt;pictureBox1.Name" xml:space="preserve">
-    <value>pictureBox1</value>
-  </data>
-  <data name="&gt;&gt;pictureBox1.Type" xml:space="preserve">
-    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;pictureBox1.Parent" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;pictureBox1.ZOrder" xml:space="preserve">
-    <value>13</value>
-  </data>
-  <data name="tabHardware.Location" type="System.Drawing.Point, System.Drawing">
-    <value>4, 22</value>
-  </data>
-  <data name="tabHardware.Padding" type="System.Windows.Forms.Padding, System.Windows.Forms">
-    <value>3, 3, 3, 3</value>
-  </data>
-  <data name="tabHardware.Size" type="System.Drawing.Size, System.Drawing">
-    <value>666, 393</value>
-  </data>
-  <data name="tabHardware.TabIndex" type="System.Int32, mscorlib">
-    <value>1</value>
-  </data>
-  <data name="tabHardware.Text" xml:space="preserve">
-    <value>Hardware</value>
-  </data>
-  <data name="&gt;&gt;tabHardware.Name" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;tabHardware.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;tabHardware.Parent" xml:space="preserve">
-    <value>Tabs</value>
-  </data>
-  <data name="&gt;&gt;tabHardware.ZOrder" xml:space="preserve">
-    <value>2</value>
-  </data>
-  <data name="&gt;&gt;groupBox4.Name" xml:space="preserve">
-    <value>groupBox4</value>
-  </data>
-  <data name="&gt;&gt;groupBox4.Type" xml:space="preserve">
-    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;groupBox4.Parent" xml:space="preserve">
-    <value>tabBattery</value>
-  </data>
-  <data name="&gt;&gt;groupBox4.ZOrder" xml:space="preserve">
-    <value>0</value>
-  </data>
-  <data name="&gt;&gt;label47.Name" xml:space="preserve">
-    <value>label47</value>
-  </data>
-  <data name="&gt;&gt;label47.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label47.Parent" xml:space="preserve">
-    <value>tabBattery</value>
-  </data>
-  <data name="&gt;&gt;label47.ZOrder" xml:space="preserve">
-    <value>1</value>
-  </data>
-  <data name="&gt;&gt;CMB_batmonsensortype.Name" xml:space="preserve">
-    <value>CMB_batmonsensortype</value>
-  </data>
-  <data name="&gt;&gt;CMB_batmonsensortype.Type" xml:space="preserve">
-    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CMB_batmonsensortype.Parent" xml:space="preserve">
-    <value>tabBattery</value>
-  </data>
-  <data name="&gt;&gt;CMB_batmonsensortype.ZOrder" xml:space="preserve">
-    <value>2</value>
-  </data>
-  <data name="&gt;&gt;textBox3.Name" xml:space="preserve">
-    <value>textBox3</value>
-  </data>
-  <data name="&gt;&gt;textBox3.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;textBox3.Parent" xml:space="preserve">
-    <value>tabBattery</value>
-  </data>
-  <data name="&gt;&gt;textBox3.ZOrder" xml:space="preserve">
-    <value>3</value>
-  </data>
-  <data name="&gt;&gt;label29.Name" xml:space="preserve">
-    <value>label29</value>
-  </data>
-  <data name="&gt;&gt;label29.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label29.Parent" xml:space="preserve">
-    <value>tabBattery</value>
-  </data>
-  <data name="&gt;&gt;label29.ZOrder" xml:space="preserve">
-    <value>4</value>
-  </data>
-  <data name="&gt;&gt;label30.Name" xml:space="preserve">
-    <value>label30</value>
-  </data>
-  <data name="&gt;&gt;label30.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label30.Parent" xml:space="preserve">
-    <value>tabBattery</value>
-  </data>
-  <data name="&gt;&gt;label30.ZOrder" xml:space="preserve">
-    <value>5</value>
-  </data>
-  <data name="&gt;&gt;TXT_battcapacity.Name" xml:space="preserve">
-    <value>TXT_battcapacity</value>
-  </data>
-  <data name="&gt;&gt;TXT_battcapacity.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;TXT_battcapacity.Parent" xml:space="preserve">
-    <value>tabBattery</value>
-  </data>
-  <data name="&gt;&gt;TXT_battcapacity.ZOrder" xml:space="preserve">
-    <value>6</value>
-  </data>
-  <data name="&gt;&gt;CMB_batmontype.Name" xml:space="preserve">
-    <value>CMB_batmontype</value>
-  </data>
-  <data name="&gt;&gt;CMB_batmontype.Type" xml:space="preserve">
-    <value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CMB_batmontype.Parent" xml:space="preserve">
-    <value>tabBattery</value>
-  </data>
-  <data name="&gt;&gt;CMB_batmontype.ZOrder" xml:space="preserve">
-    <value>7</value>
-  </data>
-  <data name="&gt;&gt;pictureBox5.Name" xml:space="preserve">
-    <value>pictureBox5</value>
-  </data>
-  <data name="&gt;&gt;pictureBox5.Type" xml:space="preserve">
-    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;pictureBox5.Parent" xml:space="preserve">
-    <value>tabBattery</value>
-  </data>
-  <data name="&gt;&gt;pictureBox5.ZOrder" xml:space="preserve">
-    <value>8</value>
-  </data>
-  <data name="tabBattery.Location" type="System.Drawing.Point, System.Drawing">
-    <value>4, 22</value>
-  </data>
-  <data name="tabBattery.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
-    <value>2, 2, 2, 2</value>
-  </data>
-  <data name="tabBattery.Size" type="System.Drawing.Size, System.Drawing">
-    <value>666, 393</value>
-  </data>
-  <data name="tabBattery.TabIndex" type="System.Int32, mscorlib">
-    <value>6</value>
-  </data>
-  <data name="tabBattery.Text" xml:space="preserve">
-    <value>Battery</value>
-  </data>
-  <data name="&gt;&gt;tabBattery.Name" xml:space="preserve">
-    <value>tabBattery</value>
-  </data>
-  <data name="&gt;&gt;tabBattery.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;tabBattery.Parent" xml:space="preserve">
-    <value>Tabs</value>
-  </data>
-  <data name="&gt;&gt;tabBattery.ZOrder" xml:space="preserve">
-    <value>3</value>
-  </data>
-  <data name="label48.AutoSize" type="System.Boolean, mscorlib">
-    <value>True</value>
-  </data>
-  <data name="label48.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
-    <value>NoControl</value>
-  </data>
-  <data name="label48.Location" type="System.Drawing.Point, System.Drawing">
-    <value>228, 170</value>
-  </data>
-  <data name="label48.Size" type="System.Drawing.Size, System.Drawing">
-    <value>212, 13</value>
-  </data>
-  <data name="label48.TabIndex" type="System.Int32, mscorlib">
-    <value>11</value>
-  </data>
-  <data name="label48.Text" xml:space="preserve">
-    <value>Level your plane to set default accel offsets</value>
-  </data>
-  <data name="&gt;&gt;label48.Name" xml:space="preserve">
-    <value>label48</value>
-  </data>
-  <data name="&gt;&gt;label48.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label48.Parent" xml:space="preserve">
-    <value>tabArduplane</value>
-  </data>
-  <data name="&gt;&gt;label48.ZOrder" xml:space="preserve">
-    <value>0</value>
-  </data>
-  <data name="BUT_levelplane.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
-    <value>NoControl</value>
-  </data>
-  <data name="BUT_levelplane.Location" type="System.Drawing.Point, System.Drawing">
-    <value>285, 199</value>
-  </data>
-  <data name="BUT_levelplane.Size" type="System.Drawing.Size, System.Drawing">
-    <value>75, 23</value>
-  </data>
-  <data name="BUT_levelplane.TabIndex" type="System.Int32, mscorlib">
-    <value>10</value>
-  </data>
-  <data name="BUT_levelplane.Text" xml:space="preserve">
-    <value>Level</value>
-  </data>
-  <data name="&gt;&gt;BUT_levelplane.Name" xml:space="preserve">
-    <value>BUT_levelplane</value>
-  </data>
-  <data name="&gt;&gt;BUT_levelplane.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;BUT_levelplane.Parent" xml:space="preserve">
-    <value>tabArduplane</value>
-  </data>
-  <data name="&gt;&gt;BUT_levelplane.ZOrder" xml:space="preserve">
-    <value>1</value>
-  </data>
-  <data name="tabArduplane.Location" type="System.Drawing.Point, System.Drawing">
-    <value>4, 22</value>
-  </data>
-  <data name="tabArduplane.Padding" type="System.Windows.Forms.Padding, System.Windows.Forms">
-    <value>3, 3, 3, 3</value>
-  </data>
-  <data name="tabArduplane.Size" type="System.Drawing.Size, System.Drawing">
-    <value>666, 393</value>
-  </data>
-  <data name="tabArduplane.TabIndex" type="System.Int32, mscorlib">
-    <value>7</value>
-  </data>
-  <data name="tabArduplane.Text" xml:space="preserve">
-    <value>ArduPlane</value>
-  </data>
-  <data name="&gt;&gt;tabArduplane.Name" xml:space="preserve">
-    <value>tabArduplane</value>
-  </data>
-  <data name="&gt;&gt;tabArduplane.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;tabArduplane.Parent" xml:space="preserve">
-    <value>Tabs</value>
-  </data>
-  <data name="&gt;&gt;tabArduplane.ZOrder" xml:space="preserve">
-    <value>4</value>
-  </data>
-  <data name="&gt;&gt;label28.Name" xml:space="preserve">
-    <value>label28</value>
-  </data>
-  <data name="&gt;&gt;label28.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label28.Parent" xml:space="preserve">
-    <value>tabArducopter</value>
-  </data>
-  <data name="&gt;&gt;label28.ZOrder" xml:space="preserve">
-    <value>0</value>
-  </data>
-  <data name="&gt;&gt;label16.Name" xml:space="preserve">
-    <value>label16</value>
-  </data>
-  <data name="&gt;&gt;label16.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label16.Parent" xml:space="preserve">
-    <value>tabArducopter</value>
-  </data>
-  <data name="&gt;&gt;label16.ZOrder" xml:space="preserve">
-    <value>1</value>
-  </data>
-  <data name="&gt;&gt;label15.Name" xml:space="preserve">
-    <value>label15</value>
-  </data>
-  <data name="&gt;&gt;label15.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label15.Parent" xml:space="preserve">
-    <value>tabArducopter</value>
-  </data>
-  <data name="&gt;&gt;label15.ZOrder" xml:space="preserve">
-    <value>2</value>
-  </data>
-  <data name="&gt;&gt;pictureBoxQuadX.Name" xml:space="preserve">
-    <value>pictureBoxQuadX</value>
-  </data>
-  <data name="&gt;&gt;pictureBoxQuadX.Type" xml:space="preserve">
-    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;pictureBoxQuadX.Parent" xml:space="preserve">
-    <value>tabArducopter</value>
-  </data>
-  <data name="&gt;&gt;pictureBoxQuadX.ZOrder" xml:space="preserve">
-    <value>3</value>
-  </data>
-  <data name="&gt;&gt;pictureBoxQuad.Name" xml:space="preserve">
-    <value>pictureBoxQuad</value>
-  </data>
-  <data name="&gt;&gt;pictureBoxQuad.Type" xml:space="preserve">
-    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;pictureBoxQuad.Parent" xml:space="preserve">
-    <value>tabArducopter</value>
-  </data>
-  <data name="&gt;&gt;pictureBoxQuad.ZOrder" xml:space="preserve">
-    <value>4</value>
-  </data>
-  <data name="&gt;&gt;BUT_levelac2.Name" xml:space="preserve">
-    <value>BUT_levelac2</value>
-  </data>
-  <data name="&gt;&gt;BUT_levelac2.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;BUT_levelac2.Parent" xml:space="preserve">
-    <value>tabArducopter</value>
-  </data>
-  <data name="&gt;&gt;BUT_levelac2.ZOrder" xml:space="preserve">
-    <value>5</value>
-  </data>
-  <data name="tabArducopter.Location" type="System.Drawing.Point, System.Drawing">
-    <value>4, 22</value>
-  </data>
-  <data name="tabArducopter.Size" type="System.Drawing.Size, System.Drawing">
-    <value>666, 393</value>
-  </data>
-  <data name="tabArducopter.TabIndex" type="System.Int32, mscorlib">
-    <value>2</value>
-  </data>
-  <data name="tabArducopter.Text" xml:space="preserve">
-    <value>ArduCopter2</value>
-  </data>
-  <data name="&gt;&gt;tabArducopter.Name" xml:space="preserve">
-    <value>tabArducopter</value>
-  </data>
-  <data name="&gt;&gt;tabArducopter.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;tabArducopter.Parent" xml:space="preserve">
-    <value>Tabs</value>
-  </data>
-  <data name="&gt;&gt;tabArducopter.ZOrder" xml:space="preserve">
-    <value>5</value>
-  </data>
-  <data name="&gt;&gt;groupBox5.Name" xml:space="preserve">
-    <value>groupBox5</value>
-  </data>
-  <data name="&gt;&gt;groupBox5.Type" xml:space="preserve">
-    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;groupBox5.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;groupBox5.ZOrder" xml:space="preserve">
-    <value>0</value>
-  </data>
-  <data name="&gt;&gt;BUT_HS4save.Name" xml:space="preserve">
-    <value>BUT_HS4save</value>
-  </data>
-  <data name="&gt;&gt;BUT_HS4save.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;BUT_HS4save.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;BUT_HS4save.ZOrder" xml:space="preserve">
-    <value>1</value>
-  </data>
-  <data name="&gt;&gt;BUT_swash_manual.Name" xml:space="preserve">
-    <value>BUT_swash_manual</value>
-  </data>
-  <data name="&gt;&gt;BUT_swash_manual.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;BUT_swash_manual.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;BUT_swash_manual.ZOrder" xml:space="preserve">
-    <value>2</value>
-  </data>
-  <data name="&gt;&gt;groupBox3.Name" xml:space="preserve">
-    <value>groupBox3</value>
-  </data>
-  <data name="&gt;&gt;groupBox3.Type" xml:space="preserve">
-    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;groupBox3.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;groupBox3.ZOrder" xml:space="preserve">
-    <value>3</value>
-  </data>
-  <data name="&gt;&gt;label44.Name" xml:space="preserve">
-    <value>label44</value>
-  </data>
-  <data name="&gt;&gt;label44.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label44.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;label44.ZOrder" xml:space="preserve">
-    <value>4</value>
-  </data>
-  <data name="&gt;&gt;label43.Name" xml:space="preserve">
-    <value>label43</value>
-  </data>
-  <data name="&gt;&gt;label43.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label43.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;label43.ZOrder" xml:space="preserve">
-    <value>5</value>
-  </data>
-  <data name="&gt;&gt;label42.Name" xml:space="preserve">
-    <value>label42</value>
-  </data>
-  <data name="&gt;&gt;label42.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label42.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;label42.ZOrder" xml:space="preserve">
-    <value>6</value>
-  </data>
-  <data name="&gt;&gt;groupBox2.Name" xml:space="preserve">
-    <value>groupBox2</value>
-  </data>
-  <data name="&gt;&gt;groupBox2.Type" xml:space="preserve">
-    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;groupBox2.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;groupBox2.ZOrder" xml:space="preserve">
-    <value>7</value>
-  </data>
-  <data name="&gt;&gt;groupBox1.Name" xml:space="preserve">
-    <value>groupBox1</value>
-  </data>
-  <data name="&gt;&gt;groupBox1.Type" xml:space="preserve">
-    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;groupBox1.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;groupBox1.ZOrder" xml:space="preserve">
-    <value>8</value>
-  </data>
-  <data name="&gt;&gt;HS4_TRIM.Name" xml:space="preserve">
-    <value>HS4_TRIM</value>
-  </data>
-  <data name="&gt;&gt;HS4_TRIM.Type" xml:space="preserve">
-    <value>System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;HS4_TRIM.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;HS4_TRIM.ZOrder" xml:space="preserve">
-    <value>9</value>
-  </data>
-  <data name="&gt;&gt;HS3_TRIM.Name" xml:space="preserve">
-    <value>HS3_TRIM</value>
-  </data>
-  <data name="&gt;&gt;HS3_TRIM.Type" xml:space="preserve">
-    <value>System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;HS3_TRIM.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;HS3_TRIM.ZOrder" xml:space="preserve">
-    <value>10</value>
-  </data>
-  <data name="&gt;&gt;HS2_TRIM.Name" xml:space="preserve">
-    <value>HS2_TRIM</value>
-  </data>
-  <data name="&gt;&gt;HS2_TRIM.Type" xml:space="preserve">
-    <value>System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;HS2_TRIM.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;HS2_TRIM.ZOrder" xml:space="preserve">
-    <value>11</value>
-  </data>
-  <data name="&gt;&gt;HS1_TRIM.Name" xml:space="preserve">
-    <value>HS1_TRIM</value>
-  </data>
-  <data name="&gt;&gt;HS1_TRIM.Type" xml:space="preserve">
-    <value>System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;HS1_TRIM.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;HS1_TRIM.ZOrder" xml:space="preserve">
-    <value>12</value>
-  </data>
-  <data name="&gt;&gt;label39.Name" xml:space="preserve">
-    <value>label39</value>
-  </data>
-  <data name="&gt;&gt;label39.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label39.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;label39.ZOrder" xml:space="preserve">
-    <value>13</value>
-  </data>
-  <data name="&gt;&gt;label38.Name" xml:space="preserve">
-    <value>label38</value>
-  </data>
-  <data name="&gt;&gt;label38.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label38.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;label38.ZOrder" xml:space="preserve">
-    <value>14</value>
-  </data>
-  <data name="&gt;&gt;label37.Name" xml:space="preserve">
-    <value>label37</value>
-  </data>
-  <data name="&gt;&gt;label37.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label37.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;label37.ZOrder" xml:space="preserve">
-    <value>15</value>
-  </data>
-  <data name="&gt;&gt;label36.Name" xml:space="preserve">
-    <value>label36</value>
-  </data>
-  <data name="&gt;&gt;label36.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label36.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;label36.ZOrder" xml:space="preserve">
-    <value>16</value>
-  </data>
-  <data name="&gt;&gt;label26.Name" xml:space="preserve">
-    <value>label26</value>
-  </data>
-  <data name="&gt;&gt;label26.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label26.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;label26.ZOrder" xml:space="preserve">
-    <value>17</value>
-  </data>
-  <data name="&gt;&gt;PIT_MAX.Name" xml:space="preserve">
-    <value>PIT_MAX</value>
-  </data>
-  <data name="&gt;&gt;PIT_MAX.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;PIT_MAX.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;PIT_MAX.ZOrder" xml:space="preserve">
-    <value>18</value>
-  </data>
-  <data name="&gt;&gt;label25.Name" xml:space="preserve">
-    <value>label25</value>
-  </data>
-  <data name="&gt;&gt;label25.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label25.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;label25.ZOrder" xml:space="preserve">
-    <value>19</value>
-  </data>
-  <data name="&gt;&gt;ROL_MAX.Name" xml:space="preserve">
-    <value>ROL_MAX</value>
-  </data>
-  <data name="&gt;&gt;ROL_MAX.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;ROL_MAX.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;ROL_MAX.ZOrder" xml:space="preserve">
-    <value>20</value>
-  </data>
-  <data name="&gt;&gt;label23.Name" xml:space="preserve">
-    <value>label23</value>
-  </data>
-  <data name="&gt;&gt;label23.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label23.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;label23.ZOrder" xml:space="preserve">
-    <value>21</value>
-  </data>
-  <data name="&gt;&gt;label22.Name" xml:space="preserve">
-    <value>label22</value>
-  </data>
-  <data name="&gt;&gt;label22.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label22.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;label22.ZOrder" xml:space="preserve">
-    <value>22</value>
-  </data>
-  <data name="&gt;&gt;HS4_REV.Name" xml:space="preserve">
-    <value>HS4_REV</value>
-  </data>
-  <data name="&gt;&gt;HS4_REV.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;HS4_REV.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;HS4_REV.ZOrder" xml:space="preserve">
-    <value>23</value>
-  </data>
-  <data name="&gt;&gt;label20.Name" xml:space="preserve">
-    <value>label20</value>
-  </data>
-  <data name="&gt;&gt;label20.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label20.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;label20.ZOrder" xml:space="preserve">
-    <value>24</value>
-  </data>
-  <data name="&gt;&gt;label19.Name" xml:space="preserve">
-    <value>label19</value>
-  </data>
-  <data name="&gt;&gt;label19.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label19.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;label19.ZOrder" xml:space="preserve">
-    <value>25</value>
-  </data>
-  <data name="&gt;&gt;label18.Name" xml:space="preserve">
-    <value>label18</value>
-  </data>
-  <data name="&gt;&gt;label18.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label18.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;label18.ZOrder" xml:space="preserve">
-    <value>26</value>
-  </data>
-  <data name="&gt;&gt;SV3_POS.Name" xml:space="preserve">
-    <value>SV3_POS</value>
-  </data>
-  <data name="&gt;&gt;SV3_POS.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;SV3_POS.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;SV3_POS.ZOrder" xml:space="preserve">
-    <value>27</value>
-  </data>
-  <data name="&gt;&gt;SV2_POS.Name" xml:space="preserve">
-    <value>SV2_POS</value>
-  </data>
-  <data name="&gt;&gt;SV2_POS.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;SV2_POS.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;SV2_POS.ZOrder" xml:space="preserve">
-    <value>28</value>
-  </data>
-  <data name="&gt;&gt;SV1_POS.Name" xml:space="preserve">
-    <value>SV1_POS</value>
-  </data>
-  <data name="&gt;&gt;SV1_POS.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;SV1_POS.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;SV1_POS.ZOrder" xml:space="preserve">
-    <value>29</value>
-  </data>
-  <data name="&gt;&gt;HS3_REV.Name" xml:space="preserve">
-    <value>HS3_REV</value>
-  </data>
-  <data name="&gt;&gt;HS3_REV.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;HS3_REV.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;HS3_REV.ZOrder" xml:space="preserve">
-    <value>30</value>
-  </data>
-  <data name="&gt;&gt;HS2_REV.Name" xml:space="preserve">
-    <value>HS2_REV</value>
-  </data>
-  <data name="&gt;&gt;HS2_REV.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;HS2_REV.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;HS2_REV.ZOrder" xml:space="preserve">
-    <value>31</value>
-  </data>
-  <data name="&gt;&gt;HS1_REV.Name" xml:space="preserve">
-    <value>HS1_REV</value>
-  </data>
-  <data name="&gt;&gt;HS1_REV.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;HS1_REV.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;HS1_REV.ZOrder" xml:space="preserve">
-    <value>32</value>
-  </data>
-  <data name="&gt;&gt;label17.Name" xml:space="preserve">
-    <value>label17</value>
-  </data>
-  <data name="&gt;&gt;label17.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label17.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;label17.ZOrder" xml:space="preserve">
-    <value>33</value>
-  </data>
-  <data name="&gt;&gt;HS4.Name" xml:space="preserve">
-    <value>HS4</value>
-  </data>
-  <data name="&gt;&gt;HS4.Type" xml:space="preserve">
-    <value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;HS4.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;HS4.ZOrder" xml:space="preserve">
-    <value>34</value>
-  </data>
-  <data name="&gt;&gt;HS3.Name" xml:space="preserve">
-    <value>HS3</value>
-  </data>
-  <data name="&gt;&gt;HS3.Type" xml:space="preserve">
-    <value>ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;HS3.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;HS3.ZOrder" xml:space="preserve">
-    <value>35</value>
-  </data>
-  <data name="&gt;&gt;Gservoloc.Name" xml:space="preserve">
-    <value>Gservoloc</value>
-  </data>
-  <data name="&gt;&gt;Gservoloc.Type" xml:space="preserve">
-    <value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;Gservoloc.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;Gservoloc.ZOrder" xml:space="preserve">
-    <value>36</value>
-  </data>
-  <data name="tabHeli.Location" type="System.Drawing.Point, System.Drawing">
-    <value>4, 22</value>
-  </data>
-  <data name="tabHeli.Size" type="System.Drawing.Size, System.Drawing">
-    <value>666, 393</value>
-  </data>
-  <data name="tabHeli.TabIndex" type="System.Int32, mscorlib">
-    <value>5</value>
-  </data>
-  <data name="tabHeli.Text" xml:space="preserve">
-    <value>AC2 Heli</value>
-  </data>
-  <data name="&gt;&gt;tabHeli.Name" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;tabHeli.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;tabHeli.Parent" xml:space="preserve">
-    <value>Tabs</value>
-  </data>
-  <data name="&gt;&gt;tabHeli.ZOrder" xml:space="preserve">
-    <value>6</value>
-  </data>
-  <data name="Tabs.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
-    <value>Fill</value>
-  </data>
-  <data name="Tabs.Location" type="System.Drawing.Point, System.Drawing">
-    <value>0, 0</value>
-  </data>
-  <data name="Tabs.Size" type="System.Drawing.Size, System.Drawing">
-    <value>674, 419</value>
-  </data>
-  <data name="Tabs.TabIndex" type="System.Int32, mscorlib">
-    <value>93</value>
-  </data>
-  <data name="&gt;&gt;Tabs.Name" xml:space="preserve">
-    <value>Tabs</value>
-  </data>
-  <data name="&gt;&gt;Tabs.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;Tabs.Parent" xml:space="preserve">
-    <value>$this</value>
-  </data>
-  <data name="&gt;&gt;Tabs.ZOrder" xml:space="preserve">
-    <value>0</value>
-  </data>
-  <data name="&gt;&gt;CHK_mixmode.Name" xml:space="preserve">
-    <value>CHK_mixmode</value>
-  </data>
-  <data name="&gt;&gt;CHK_mixmode.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CHK_mixmode.Parent" xml:space="preserve">
-    <value>groupBoxElevons</value>
-  </data>
-  <data name="&gt;&gt;CHK_mixmode.ZOrder" xml:space="preserve">
-    <value>0</value>
-  </data>
-  <data name="&gt;&gt;CHK_elevonch2rev.Name" xml:space="preserve">
-    <value>CHK_elevonch2rev</value>
-  </data>
-  <data name="&gt;&gt;CHK_elevonch2rev.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CHK_elevonch2rev.Parent" xml:space="preserve">
-    <value>groupBoxElevons</value>
-  </data>
-  <data name="&gt;&gt;CHK_elevonch2rev.ZOrder" xml:space="preserve">
-    <value>1</value>
-  </data>
-  <data name="&gt;&gt;CHK_elevonrev.Name" xml:space="preserve">
-    <value>CHK_elevonrev</value>
-  </data>
-  <data name="&gt;&gt;CHK_elevonrev.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CHK_elevonrev.Parent" xml:space="preserve">
-    <value>groupBoxElevons</value>
-  </data>
-  <data name="&gt;&gt;CHK_elevonrev.ZOrder" xml:space="preserve">
-    <value>2</value>
-  </data>
-  <data name="&gt;&gt;CHK_elevonch1rev.Name" xml:space="preserve">
-    <value>CHK_elevonch1rev</value>
-  </data>
-  <data name="&gt;&gt;CHK_elevonch1rev.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CHK_elevonch1rev.Parent" xml:space="preserve">
-    <value>groupBoxElevons</value>
-  </data>
-  <data name="&gt;&gt;CHK_elevonch1rev.ZOrder" xml:space="preserve">
-    <value>3</value>
-  </data>
-  <data name="groupBoxElevons.Location" type="System.Drawing.Point, System.Drawing">
-    <value>21, 349</value>
-  </data>
-  <data name="groupBoxElevons.Size" type="System.Drawing.Size, System.Drawing">
-    <value>409, 42</value>
-  </data>
-  <data name="groupBoxElevons.TabIndex" type="System.Int32, mscorlib">
-    <value>111</value>
-  </data>
-  <data name="groupBoxElevons.Text" xml:space="preserve">
-    <value>Elevon Config</value>
-  </data>
-  <data name="&gt;&gt;groupBoxElevons.Name" xml:space="preserve">
-    <value>groupBoxElevons</value>
-  </data>
-  <data name="&gt;&gt;groupBoxElevons.Type" xml:space="preserve">
-    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;groupBoxElevons.Parent" xml:space="preserve">
-    <value>tabRadioIn</value>
-  </data>
-  <data name="&gt;&gt;groupBoxElevons.ZOrder" xml:space="preserve">
-    <value>0</value>
-  </data>
+  <assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
   <data name="CHK_mixmode.AutoSize" type="System.Boolean, mscorlib">
     <value>True</value>
   </data>
+  <assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
   <data name="CHK_mixmode.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
     <value>NoControl</value>
   </data>
+  <assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
   <data name="CHK_mixmode.Location" type="System.Drawing.Point, System.Drawing">
     <value>13, 19</value>
   </data>
@@ -1896,6 +255,30 @@
   <data name="&gt;&gt;CHK_elevonch1rev.ZOrder" xml:space="preserve">
     <value>3</value>
   </data>
+  <data name="groupBoxElevons.Location" type="System.Drawing.Point, System.Drawing">
+    <value>21, 349</value>
+  </data>
+  <data name="groupBoxElevons.Size" type="System.Drawing.Size, System.Drawing">
+    <value>409, 42</value>
+  </data>
+  <data name="groupBoxElevons.TabIndex" type="System.Int32, mscorlib">
+    <value>111</value>
+  </data>
+  <data name="groupBoxElevons.Text" xml:space="preserve">
+    <value>Elevon Config</value>
+  </data>
+  <data name="&gt;&gt;groupBoxElevons.Name" xml:space="preserve">
+    <value>groupBoxElevons</value>
+  </data>
+  <data name="&gt;&gt;groupBoxElevons.Type" xml:space="preserve">
+    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;groupBoxElevons.Parent" xml:space="preserve">
+    <value>tabRadioIn</value>
+  </data>
+  <data name="&gt;&gt;groupBoxElevons.ZOrder" xml:space="preserve">
+    <value>0</value>
+  </data>
   <data name="CHK_revch3.AutoSize" type="System.Boolean, mscorlib">
     <value>True</value>
   </data>
@@ -2067,9 +450,6 @@
   <data name="&gt;&gt;BAR8.ZOrder" xml:space="preserve">
     <value>6</value>
   </data>
-  <metadata name="currentStateBindingSource.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
-    <value>17, 17</value>
-  </metadata>
   <data name="BAR7.Location" type="System.Drawing.Point, System.Drawing">
     <value>446, 185</value>
   </data>
@@ -2217,6 +597,33 @@
   <data name="&gt;&gt;BARroll.ZOrder" xml:space="preserve">
     <value>13</value>
   </data>
+  <data name="tabRadioIn.Location" type="System.Drawing.Point, System.Drawing">
+    <value>4, 22</value>
+  </data>
+  <data name="tabRadioIn.Padding" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>3, 3, 3, 3</value>
+  </data>
+  <data name="tabRadioIn.Size" type="System.Drawing.Size, System.Drawing">
+    <value>666, 393</value>
+  </data>
+  <data name="tabRadioIn.TabIndex" type="System.Int32, mscorlib">
+    <value>0</value>
+  </data>
+  <data name="tabRadioIn.Text" xml:space="preserve">
+    <value>Radio Input</value>
+  </data>
+  <data name="&gt;&gt;tabRadioIn.Name" xml:space="preserve">
+    <value>tabRadioIn</value>
+  </data>
+  <data name="&gt;&gt;tabRadioIn.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;tabRadioIn.Parent" xml:space="preserve">
+    <value>Tabs</value>
+  </data>
+  <data name="&gt;&gt;tabRadioIn.ZOrder" xml:space="preserve">
+    <value>0</value>
+  </data>
   <data name="CB_simple6.AutoSize" type="System.Boolean, mscorlib">
     <value>True</value>
   </data>
@@ -3048,6 +1455,30 @@
   <data name="&gt;&gt;BUT_SaveModes.ZOrder" xml:space="preserve">
     <value>28</value>
   </data>
+  <data name="tabModes.Location" type="System.Drawing.Point, System.Drawing">
+    <value>4, 22</value>
+  </data>
+  <data name="tabModes.Size" type="System.Drawing.Size, System.Drawing">
+    <value>666, 393</value>
+  </data>
+  <data name="tabModes.TabIndex" type="System.Int32, mscorlib">
+    <value>3</value>
+  </data>
+  <data name="tabModes.Text" xml:space="preserve">
+    <value>Modes</value>
+  </data>
+  <data name="&gt;&gt;tabModes.Name" xml:space="preserve">
+    <value>tabModes</value>
+  </data>
+  <data name="&gt;&gt;tabModes.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;tabModes.Parent" xml:space="preserve">
+    <value>Tabs</value>
+  </data>
+  <data name="&gt;&gt;tabModes.ZOrder" xml:space="preserve">
+    <value>1</value>
+  </data>
   <data name="BUT_MagCalibration.Location" type="System.Drawing.Point, System.Drawing">
     <value>405, 25</value>
   </data>
@@ -3366,215 +1797,98 @@
   <data name="&gt;&gt;pictureBox4.Type" xml:space="preserve">
     <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
   </data>
-  <data name="&gt;&gt;pictureBox4.Parent" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;pictureBox4.ZOrder" xml:space="preserve">
-    <value>11</value>
-  </data>
-  <data name="pictureBox3.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
-    <value>Zoom</value>
-  </data>
-  <data name="pictureBox3.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
-    <value>NoControl</value>
-  </data>
-  <data name="pictureBox3.Location" type="System.Drawing.Point, System.Drawing">
-    <value>78, 106</value>
-  </data>
-  <data name="pictureBox3.Size" type="System.Drawing.Size, System.Drawing">
-    <value>75, 75</value>
-  </data>
-  <data name="pictureBox3.TabIndex" type="System.Int32, mscorlib">
-    <value>2</value>
-  </data>
-  <data name="&gt;&gt;pictureBox3.Name" xml:space="preserve">
-    <value>pictureBox3</value>
-  </data>
-  <data name="&gt;&gt;pictureBox3.Type" xml:space="preserve">
-    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;pictureBox3.Parent" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;pictureBox3.ZOrder" xml:space="preserve">
-    <value>12</value>
-  </data>
-  <data name="pictureBox1.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
-    <value>Zoom</value>
-  </data>
-  <data name="pictureBox1.ErrorImage" type="System.Resources.ResXNullRef, System.Windows.Forms">
-    <value />
-  </data>
-  <data name="pictureBox1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
-    <value>NoControl</value>
-  </data>
-  <data name="pictureBox1.InitialImage" type="System.Resources.ResXNullRef, System.Windows.Forms">
-    <value />
-  </data>
-  <data name="pictureBox1.Location" type="System.Drawing.Point, System.Drawing">
-    <value>78, 25</value>
-  </data>
-  <data name="pictureBox1.Size" type="System.Drawing.Size, System.Drawing">
-    <value>75, 75</value>
-  </data>
-  <data name="pictureBox1.TabIndex" type="System.Int32, mscorlib">
-    <value>0</value>
-  </data>
-  <data name="&gt;&gt;pictureBox1.Name" xml:space="preserve">
-    <value>pictureBox1</value>
-  </data>
-  <data name="&gt;&gt;pictureBox1.Type" xml:space="preserve">
-    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;pictureBox1.Parent" xml:space="preserve">
-    <value>tabHardware</value>
-  </data>
-  <data name="&gt;&gt;pictureBox1.ZOrder" xml:space="preserve">
-    <value>13</value>
-  </data>
-  <data name="&gt;&gt;label31.Name" xml:space="preserve">
-    <value>label31</value>
-  </data>
-  <data name="&gt;&gt;label31.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label31.Parent" xml:space="preserve">
-    <value>groupBox4</value>
-  </data>
-  <data name="&gt;&gt;label31.ZOrder" xml:space="preserve">
-    <value>0</value>
-  </data>
-  <data name="&gt;&gt;label32.Name" xml:space="preserve">
-    <value>label32</value>
-  </data>
-  <data name="&gt;&gt;label32.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label32.Parent" xml:space="preserve">
-    <value>groupBox4</value>
-  </data>
-  <data name="&gt;&gt;label32.ZOrder" xml:space="preserve">
-    <value>1</value>
-  </data>
-  <data name="&gt;&gt;label33.Name" xml:space="preserve">
-    <value>label33</value>
-  </data>
-  <data name="&gt;&gt;label33.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label33.Parent" xml:space="preserve">
-    <value>groupBox4</value>
-  </data>
-  <data name="&gt;&gt;label33.ZOrder" xml:space="preserve">
-    <value>2</value>
-  </data>
-  <data name="&gt;&gt;TXT_ampspervolt.Name" xml:space="preserve">
-    <value>TXT_ampspervolt</value>
-  </data>
-  <data name="&gt;&gt;TXT_ampspervolt.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;TXT_ampspervolt.Parent" xml:space="preserve">
-    <value>groupBox4</value>
-  </data>
-  <data name="&gt;&gt;TXT_ampspervolt.ZOrder" xml:space="preserve">
-    <value>3</value>
-  </data>
-  <data name="&gt;&gt;label34.Name" xml:space="preserve">
-    <value>label34</value>
-  </data>
-  <data name="&gt;&gt;label34.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label34.Parent" xml:space="preserve">
-    <value>groupBox4</value>
+  <data name="&gt;&gt;pictureBox4.Parent" xml:space="preserve">
+    <value>tabHardware</value>
   </data>
-  <data name="&gt;&gt;label34.ZOrder" xml:space="preserve">
-    <value>4</value>
+  <data name="&gt;&gt;pictureBox4.ZOrder" xml:space="preserve">
+    <value>11</value>
   </data>
-  <data name="&gt;&gt;TXT_divider.Name" xml:space="preserve">
-    <value>TXT_divider</value>
+  <data name="pictureBox3.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
+    <value>Zoom</value>
   </data>
-  <data name="&gt;&gt;TXT_divider.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  <data name="pictureBox3.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
   </data>
-  <data name="&gt;&gt;TXT_divider.Parent" xml:space="preserve">
-    <value>groupBox4</value>
+  <data name="pictureBox3.Location" type="System.Drawing.Point, System.Drawing">
+    <value>78, 106</value>
   </data>
-  <data name="&gt;&gt;TXT_divider.ZOrder" xml:space="preserve">
-    <value>5</value>
+  <data name="pictureBox3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>75, 75</value>
   </data>
-  <data name="&gt;&gt;label35.Name" xml:space="preserve">
-    <value>label35</value>
+  <data name="pictureBox3.TabIndex" type="System.Int32, mscorlib">
+    <value>2</value>
   </data>
-  <data name="&gt;&gt;label35.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  <data name="&gt;&gt;pictureBox3.Name" xml:space="preserve">
+    <value>pictureBox3</value>
   </data>
-  <data name="&gt;&gt;label35.Parent" xml:space="preserve">
-    <value>groupBox4</value>
+  <data name="&gt;&gt;pictureBox3.Type" xml:space="preserve">
+    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
   </data>
-  <data name="&gt;&gt;label35.ZOrder" xml:space="preserve">
-    <value>6</value>
+  <data name="&gt;&gt;pictureBox3.Parent" xml:space="preserve">
+    <value>tabHardware</value>
   </data>
-  <data name="&gt;&gt;TXT_voltage.Name" xml:space="preserve">
-    <value>TXT_voltage</value>
+  <data name="&gt;&gt;pictureBox3.ZOrder" xml:space="preserve">
+    <value>12</value>
   </data>
-  <data name="&gt;&gt;TXT_voltage.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  <data name="pictureBox1.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
+    <value>Zoom</value>
   </data>
-  <data name="&gt;&gt;TXT_voltage.Parent" xml:space="preserve">
-    <value>groupBox4</value>
+  <data name="pictureBox1.ErrorImage" type="System.Resources.ResXNullRef, System.Windows.Forms">
+    <value />
   </data>
-  <data name="&gt;&gt;TXT_voltage.ZOrder" xml:space="preserve">
-    <value>7</value>
+  <data name="pictureBox1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
   </data>
-  <data name="&gt;&gt;TXT_inputvoltage.Name" xml:space="preserve">
-    <value>TXT_inputvoltage</value>
+  <data name="pictureBox1.InitialImage" type="System.Resources.ResXNullRef, System.Windows.Forms">
+    <value />
   </data>
-  <data name="&gt;&gt;TXT_inputvoltage.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  <data name="pictureBox1.Location" type="System.Drawing.Point, System.Drawing">
+    <value>78, 25</value>
   </data>
-  <data name="&gt;&gt;TXT_inputvoltage.Parent" xml:space="preserve">
-    <value>groupBox4</value>
+  <data name="pictureBox1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>75, 75</value>
   </data>
-  <data name="&gt;&gt;TXT_inputvoltage.ZOrder" xml:space="preserve">
-    <value>8</value>
+  <data name="pictureBox1.TabIndex" type="System.Int32, mscorlib">
+    <value>0</value>
   </data>
-  <data name="&gt;&gt;TXT_measuredvoltage.Name" xml:space="preserve">
-    <value>TXT_measuredvoltage</value>
+  <data name="&gt;&gt;pictureBox1.Name" xml:space="preserve">
+    <value>pictureBox1</value>
   </data>
-  <data name="&gt;&gt;TXT_measuredvoltage.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  <data name="&gt;&gt;pictureBox1.Type" xml:space="preserve">
+    <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
   </data>
-  <data name="&gt;&gt;TXT_measuredvoltage.Parent" xml:space="preserve">
-    <value>groupBox4</value>
+  <data name="&gt;&gt;pictureBox1.Parent" xml:space="preserve">
+    <value>tabHardware</value>
   </data>
-  <data name="&gt;&gt;TXT_measuredvoltage.ZOrder" xml:space="preserve">
-    <value>9</value>
+  <data name="&gt;&gt;pictureBox1.ZOrder" xml:space="preserve">
+    <value>13</value>
   </data>
-  <data name="groupBox4.Location" type="System.Drawing.Point, System.Drawing">
-    <value>31, 177</value>
+  <data name="tabHardware.Location" type="System.Drawing.Point, System.Drawing">
+    <value>4, 22</value>
   </data>
-  <data name="groupBox4.Size" type="System.Drawing.Size, System.Drawing">
-    <value>238, 131</value>
+  <data name="tabHardware.Padding" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>3, 3, 3, 3</value>
   </data>
-  <data name="groupBox4.TabIndex" type="System.Int32, mscorlib">
-    <value>41</value>
+  <data name="tabHardware.Size" type="System.Drawing.Size, System.Drawing">
+    <value>666, 393</value>
   </data>
-  <data name="groupBox4.Text" xml:space="preserve">
-    <value>Calibration</value>
+  <data name="tabHardware.TabIndex" type="System.Int32, mscorlib">
+    <value>1</value>
   </data>
-  <data name="&gt;&gt;groupBox4.Name" xml:space="preserve">
-    <value>groupBox4</value>
+  <data name="tabHardware.Text" xml:space="preserve">
+    <value>Hardware</value>
   </data>
-  <data name="&gt;&gt;groupBox4.Type" xml:space="preserve">
-    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  <data name="&gt;&gt;tabHardware.Name" xml:space="preserve">
+    <value>tabHardware</value>
   </data>
-  <data name="&gt;&gt;groupBox4.Parent" xml:space="preserve">
-    <value>tabBattery</value>
+  <data name="&gt;&gt;tabHardware.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
   </data>
-  <data name="&gt;&gt;groupBox4.ZOrder" xml:space="preserve">
-    <value>0</value>
+  <data name="&gt;&gt;tabHardware.Parent" xml:space="preserve">
+    <value>Tabs</value>
+  </data>
+  <data name="&gt;&gt;tabHardware.ZOrder" xml:space="preserve">
+    <value>2</value>
   </data>
   <data name="label31.AutoSize" type="System.Boolean, mscorlib">
     <value>True</value>
@@ -3861,6 +2175,30 @@
   <data name="&gt;&gt;TXT_measuredvoltage.ZOrder" xml:space="preserve">
     <value>9</value>
   </data>
+  <data name="groupBox4.Location" type="System.Drawing.Point, System.Drawing">
+    <value>31, 177</value>
+  </data>
+  <data name="groupBox4.Size" type="System.Drawing.Size, System.Drawing">
+    <value>238, 131</value>
+  </data>
+  <data name="groupBox4.TabIndex" type="System.Int32, mscorlib">
+    <value>41</value>
+  </data>
+  <data name="groupBox4.Text" xml:space="preserve">
+    <value>Calibration</value>
+  </data>
+  <data name="&gt;&gt;groupBox4.Name" xml:space="preserve">
+    <value>groupBox4</value>
+  </data>
+  <data name="&gt;&gt;groupBox4.Type" xml:space="preserve">
+    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;groupBox4.Parent" xml:space="preserve">
+    <value>tabBattery</value>
+  </data>
+  <data name="&gt;&gt;groupBox4.ZOrder" xml:space="preserve">
+    <value>0</value>
+  </data>
   <data name="label47.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
     <value>NoControl</value>
   </data>
@@ -4086,11 +2424,122 @@ Then subtract 0.3v from that value and enter it in field #1 at left.
   <data name="&gt;&gt;pictureBox5.Type" xml:space="preserve">
     <value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
   </data>
-  <data name="&gt;&gt;pictureBox5.Parent" xml:space="preserve">
-    <value>tabBattery</value>
+  <data name="&gt;&gt;pictureBox5.Parent" xml:space="preserve">
+    <value>tabBattery</value>
+  </data>
+  <data name="&gt;&gt;pictureBox5.ZOrder" xml:space="preserve">
+    <value>8</value>
+  </data>
+  <data name="tabBattery.Location" type="System.Drawing.Point, System.Drawing">
+    <value>4, 22</value>
+  </data>
+  <data name="tabBattery.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>2, 2, 2, 2</value>
+  </data>
+  <data name="tabBattery.Size" type="System.Drawing.Size, System.Drawing">
+    <value>666, 393</value>
+  </data>
+  <data name="tabBattery.TabIndex" type="System.Int32, mscorlib">
+    <value>6</value>
+  </data>
+  <data name="tabBattery.Text" xml:space="preserve">
+    <value>Battery</value>
+  </data>
+  <data name="&gt;&gt;tabBattery.Name" xml:space="preserve">
+    <value>tabBattery</value>
+  </data>
+  <data name="&gt;&gt;tabBattery.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;tabBattery.Parent" xml:space="preserve">
+    <value>Tabs</value>
+  </data>
+  <data name="&gt;&gt;tabBattery.ZOrder" xml:space="preserve">
+    <value>3</value>
+  </data>
+  <data name="label48.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
+  </data>
+  <data name="label48.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="label48.Location" type="System.Drawing.Point, System.Drawing">
+    <value>228, 170</value>
+  </data>
+  <data name="label48.Size" type="System.Drawing.Size, System.Drawing">
+    <value>212, 13</value>
+  </data>
+  <data name="label48.TabIndex" type="System.Int32, mscorlib">
+    <value>11</value>
+  </data>
+  <data name="label48.Text" xml:space="preserve">
+    <value>Level your plane to set default accel offsets</value>
+  </data>
+  <data name="&gt;&gt;label48.Name" xml:space="preserve">
+    <value>label48</value>
+  </data>
+  <data name="&gt;&gt;label48.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;label48.Parent" xml:space="preserve">
+    <value>tabArduplane</value>
+  </data>
+  <data name="&gt;&gt;label48.ZOrder" xml:space="preserve">
+    <value>0</value>
+  </data>
+  <data name="BUT_levelplane.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
+  </data>
+  <data name="BUT_levelplane.Location" type="System.Drawing.Point, System.Drawing">
+    <value>285, 199</value>
+  </data>
+  <data name="BUT_levelplane.Size" type="System.Drawing.Size, System.Drawing">
+    <value>75, 23</value>
+  </data>
+  <data name="BUT_levelplane.TabIndex" type="System.Int32, mscorlib">
+    <value>10</value>
+  </data>
+  <data name="BUT_levelplane.Text" xml:space="preserve">
+    <value>Level</value>
+  </data>
+  <data name="&gt;&gt;BUT_levelplane.Name" xml:space="preserve">
+    <value>BUT_levelplane</value>
+  </data>
+  <data name="&gt;&gt;BUT_levelplane.Type" xml:space="preserve">
+    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  </data>
+  <data name="&gt;&gt;BUT_levelplane.Parent" xml:space="preserve">
+    <value>tabArduplane</value>
+  </data>
+  <data name="&gt;&gt;BUT_levelplane.ZOrder" xml:space="preserve">
+    <value>1</value>
+  </data>
+  <data name="tabArduplane.Location" type="System.Drawing.Point, System.Drawing">
+    <value>4, 22</value>
+  </data>
+  <data name="tabArduplane.Padding" type="System.Windows.Forms.Padding, System.Windows.Forms">
+    <value>3, 3, 3, 3</value>
+  </data>
+  <data name="tabArduplane.Size" type="System.Drawing.Size, System.Drawing">
+    <value>666, 393</value>
+  </data>
+  <data name="tabArduplane.TabIndex" type="System.Int32, mscorlib">
+    <value>7</value>
+  </data>
+  <data name="tabArduplane.Text" xml:space="preserve">
+    <value>ArduPlane</value>
+  </data>
+  <data name="&gt;&gt;tabArduplane.Name" xml:space="preserve">
+    <value>tabArduplane</value>
+  </data>
+  <data name="&gt;&gt;tabArduplane.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;tabArduplane.Parent" xml:space="preserve">
+    <value>Tabs</value>
   </data>
-  <data name="&gt;&gt;pictureBox5.ZOrder" xml:space="preserve">
-    <value>8</value>
+  <data name="&gt;&gt;tabArduplane.ZOrder" xml:space="preserve">
+    <value>4</value>
   </data>
   <data name="label28.AutoSize" type="System.Boolean, mscorlib">
     <value>True</value>
@@ -4264,53 +2713,29 @@ will work with hexa's etc</value>
   <data name="&gt;&gt;BUT_levelac2.ZOrder" xml:space="preserve">
     <value>5</value>
   </data>
-  <data name="&gt;&gt;H1_ENABLE.Name" xml:space="preserve">
-    <value>H1_ENABLE</value>
-  </data>
-  <data name="&gt;&gt;H1_ENABLE.Type" xml:space="preserve">
-    <value>System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;H1_ENABLE.Parent" xml:space="preserve">
-    <value>groupBox5</value>
-  </data>
-  <data name="&gt;&gt;H1_ENABLE.ZOrder" xml:space="preserve">
-    <value>0</value>
-  </data>
-  <data name="&gt;&gt;CCPM.Name" xml:space="preserve">
-    <value>CCPM</value>
-  </data>
-  <data name="&gt;&gt;CCPM.Type" xml:space="preserve">
-    <value>System.Windows.Forms.RadioButton, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;CCPM.Parent" xml:space="preserve">
-    <value>groupBox5</value>
-  </data>
-  <data name="&gt;&gt;CCPM.ZOrder" xml:space="preserve">
-    <value>1</value>
-  </data>
-  <data name="groupBox5.Location" type="System.Drawing.Point, System.Drawing">
-    <value>253, 6</value>
+  <data name="tabArducopter.Location" type="System.Drawing.Point, System.Drawing">
+    <value>4, 22</value>
   </data>
-  <data name="groupBox5.Size" type="System.Drawing.Size, System.Drawing">
-    <value>120, 43</value>
+  <data name="tabArducopter.Size" type="System.Drawing.Size, System.Drawing">
+    <value>666, 393</value>
   </data>
-  <data name="groupBox5.TabIndex" type="System.Int32, mscorlib">
-    <value>137</value>
+  <data name="tabArducopter.TabIndex" type="System.Int32, mscorlib">
+    <value>2</value>
   </data>
-  <data name="groupBox5.Text" xml:space="preserve">
-    <value>Swash Type</value>
+  <data name="tabArducopter.Text" xml:space="preserve">
+    <value>ArduCopter2</value>
   </data>
-  <data name="&gt;&gt;groupBox5.Name" xml:space="preserve">
-    <value>groupBox5</value>
+  <data name="&gt;&gt;tabArducopter.Name" xml:space="preserve">
+    <value>tabArducopter</value>
   </data>
-  <data name="&gt;&gt;groupBox5.Type" xml:space="preserve">
-    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  <data name="&gt;&gt;tabArducopter.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
   </data>
-  <data name="&gt;&gt;groupBox5.Parent" xml:space="preserve">
-    <value>tabHeli</value>
+  <data name="&gt;&gt;tabArducopter.Parent" xml:space="preserve">
+    <value>Tabs</value>
   </data>
-  <data name="&gt;&gt;groupBox5.ZOrder" xml:space="preserve">
-    <value>0</value>
+  <data name="&gt;&gt;tabArducopter.ZOrder" xml:space="preserve">
+    <value>5</value>
   </data>
   <data name="H1_ENABLE.AutoSize" type="System.Boolean, mscorlib">
     <value>True</value>
@@ -4369,6 +2794,30 @@ will work with hexa's etc</value>
   <data name="&gt;&gt;CCPM.ZOrder" xml:space="preserve">
     <value>1</value>
   </data>
+  <data name="groupBox5.Location" type="System.Drawing.Point, System.Drawing">
+    <value>253, 6</value>
+  </data>
+  <data name="groupBox5.Size" type="System.Drawing.Size, System.Drawing">
+    <value>120, 43</value>
+  </data>
+  <data name="groupBox5.TabIndex" type="System.Int32, mscorlib">
+    <value>137</value>
+  </data>
+  <data name="groupBox5.Text" xml:space="preserve">
+    <value>Swash Type</value>
+  </data>
+  <data name="&gt;&gt;groupBox5.Name" xml:space="preserve">
+    <value>groupBox5</value>
+  </data>
+  <data name="&gt;&gt;groupBox5.Type" xml:space="preserve">
+    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;groupBox5.Parent" xml:space="preserve">
+    <value>tabHeli</value>
+  </data>
+  <data name="&gt;&gt;groupBox5.ZOrder" xml:space="preserve">
+    <value>0</value>
+  </data>
   <data name="BUT_HS4save.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
     <value>NoControl</value>
   </data>
@@ -4423,78 +2872,6 @@ will work with hexa's etc</value>
   <data name="&gt;&gt;BUT_swash_manual.ZOrder" xml:space="preserve">
     <value>2</value>
   </data>
-  <data name="&gt;&gt;label46.Name" xml:space="preserve">
-    <value>label46</value>
-  </data>
-  <data name="&gt;&gt;label46.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label46.Parent" xml:space="preserve">
-    <value>groupBox3</value>
-  </data>
-  <data name="&gt;&gt;label46.ZOrder" xml:space="preserve">
-    <value>0</value>
-  </data>
-  <data name="&gt;&gt;label45.Name" xml:space="preserve">
-    <value>label45</value>
-  </data>
-  <data name="&gt;&gt;label45.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label45.Parent" xml:space="preserve">
-    <value>groupBox3</value>
-  </data>
-  <data name="&gt;&gt;label45.ZOrder" xml:space="preserve">
-    <value>1</value>
-  </data>
-  <data name="&gt;&gt;GYR_ENABLE.Name" xml:space="preserve">
-    <value>GYR_ENABLE</value>
-  </data>
-  <data name="&gt;&gt;GYR_ENABLE.Type" xml:space="preserve">
-    <value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;GYR_ENABLE.Parent" xml:space="preserve">
-    <value>groupBox3</value>
-  </data>
-  <data name="&gt;&gt;GYR_ENABLE.ZOrder" xml:space="preserve">
-    <value>2</value>
-  </data>
-  <data name="&gt;&gt;GYR_GAIN.Name" xml:space="preserve">
-    <value>GYR_GAIN</value>
-  </data>
-  <data name="&gt;&gt;GYR_GAIN.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;GYR_GAIN.Parent" xml:space="preserve">
-    <value>groupBox3</value>
-  </data>
-  <data name="&gt;&gt;GYR_GAIN.ZOrder" xml:space="preserve">
-    <value>3</value>
-  </data>
-  <data name="groupBox3.Location" type="System.Drawing.Point, System.Drawing">
-    <value>433, 309</value>
-  </data>
-  <data name="groupBox3.Size" type="System.Drawing.Size, System.Drawing">
-    <value>101, 63</value>
-  </data>
-  <data name="groupBox3.TabIndex" type="System.Int32, mscorlib">
-    <value>135</value>
-  </data>
-  <data name="groupBox3.Text" xml:space="preserve">
-    <value>Gyro</value>
-  </data>
-  <data name="&gt;&gt;groupBox3.Name" xml:space="preserve">
-    <value>groupBox3</value>
-  </data>
-  <data name="&gt;&gt;groupBox3.Type" xml:space="preserve">
-    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;groupBox3.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;groupBox3.ZOrder" xml:space="preserve">
-    <value>3</value>
-  </data>
   <data name="label46.AutoSize" type="System.Boolean, mscorlib">
     <value>True</value>
   </data>
@@ -4606,6 +2983,30 @@ will work with hexa's etc</value>
   <data name="&gt;&gt;GYR_GAIN.ZOrder" xml:space="preserve">
     <value>3</value>
   </data>
+  <data name="groupBox3.Location" type="System.Drawing.Point, System.Drawing">
+    <value>433, 309</value>
+  </data>
+  <data name="groupBox3.Size" type="System.Drawing.Size, System.Drawing">
+    <value>101, 63</value>
+  </data>
+  <data name="groupBox3.TabIndex" type="System.Int32, mscorlib">
+    <value>135</value>
+  </data>
+  <data name="groupBox3.Text" xml:space="preserve">
+    <value>Gyro</value>
+  </data>
+  <data name="&gt;&gt;groupBox3.Name" xml:space="preserve">
+    <value>groupBox3</value>
+  </data>
+  <data name="&gt;&gt;groupBox3.Type" xml:space="preserve">
+    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;groupBox3.Parent" xml:space="preserve">
+    <value>tabHeli</value>
+  </data>
+  <data name="&gt;&gt;groupBox3.ZOrder" xml:space="preserve">
+    <value>3</value>
+  </data>
   <data name="label44.AutoSize" type="System.Boolean, mscorlib">
     <value>True</value>
   </data>
@@ -4646,124 +3047,55 @@ will work with hexa's etc</value>
     <value>499, 263</value>
   </data>
   <data name="label43.Size" type="System.Drawing.Size, System.Drawing">
-    <value>27, 13</value>
-  </data>
-  <data name="label43.TabIndex" type="System.Int32, mscorlib">
-    <value>133</value>
-  </data>
-  <data name="label43.Text" xml:space="preserve">
-    <value>Rev</value>
-  </data>
-  <data name="&gt;&gt;label43.Name" xml:space="preserve">
-    <value>label43</value>
-  </data>
-  <data name="&gt;&gt;label43.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label43.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;label43.ZOrder" xml:space="preserve">
-    <value>5</value>
-  </data>
-  <data name="label42.AutoSize" type="System.Boolean, mscorlib">
-    <value>True</value>
-  </data>
-  <data name="label42.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
-    <value>NoControl</value>
-  </data>
-  <data name="label42.Location" type="System.Drawing.Point, System.Drawing">
-    <value>451, 283</value>
-  </data>
-  <data name="label42.Size" type="System.Drawing.Size, System.Drawing">
-    <value>42, 13</value>
-  </data>
-  <data name="label42.TabIndex" type="System.Int32, mscorlib">
-    <value>132</value>
-  </data>
-  <data name="label42.Text" xml:space="preserve">
-    <value>Rudder</value>
-  </data>
-  <data name="&gt;&gt;label42.Name" xml:space="preserve">
-    <value>label42</value>
-  </data>
-  <data name="&gt;&gt;label42.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label42.Parent" xml:space="preserve">
-    <value>tabHeli</value>
-  </data>
-  <data name="&gt;&gt;label42.ZOrder" xml:space="preserve">
-    <value>6</value>
-  </data>
-  <data name="&gt;&gt;label24.Name" xml:space="preserve">
-    <value>label24</value>
-  </data>
-  <data name="&gt;&gt;label24.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label24.Parent" xml:space="preserve">
-    <value>groupBox2</value>
-  </data>
-  <data name="&gt;&gt;label24.ZOrder" xml:space="preserve">
-    <value>0</value>
-  </data>
-  <data name="&gt;&gt;HS4_MIN.Name" xml:space="preserve">
-    <value>HS4_MIN</value>
-  </data>
-  <data name="&gt;&gt;HS4_MIN.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;HS4_MIN.Parent" xml:space="preserve">
-    <value>groupBox2</value>
+    <value>27, 13</value>
   </data>
-  <data name="&gt;&gt;HS4_MIN.ZOrder" xml:space="preserve">
-    <value>1</value>
+  <data name="label43.TabIndex" type="System.Int32, mscorlib">
+    <value>133</value>
   </data>
-  <data name="&gt;&gt;HS4_MAX.Name" xml:space="preserve">
-    <value>HS4_MAX</value>
+  <data name="label43.Text" xml:space="preserve">
+    <value>Rev</value>
   </data>
-  <data name="&gt;&gt;HS4_MAX.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  <data name="&gt;&gt;label43.Name" xml:space="preserve">
+    <value>label43</value>
   </data>
-  <data name="&gt;&gt;HS4_MAX.Parent" xml:space="preserve">
-    <value>groupBox2</value>
+  <data name="&gt;&gt;label43.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
   </data>
-  <data name="&gt;&gt;HS4_MAX.ZOrder" xml:space="preserve">
-    <value>2</value>
+  <data name="&gt;&gt;label43.Parent" xml:space="preserve">
+    <value>tabHeli</value>
   </data>
-  <data name="&gt;&gt;label40.Name" xml:space="preserve">
-    <value>label40</value>
+  <data name="&gt;&gt;label43.ZOrder" xml:space="preserve">
+    <value>5</value>
   </data>
-  <data name="&gt;&gt;label40.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  <data name="label42.AutoSize" type="System.Boolean, mscorlib">
+    <value>True</value>
   </data>
-  <data name="&gt;&gt;label40.Parent" xml:space="preserve">
-    <value>groupBox2</value>
+  <data name="label42.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
+    <value>NoControl</value>
   </data>
-  <data name="&gt;&gt;label40.ZOrder" xml:space="preserve">
-    <value>3</value>
+  <data name="label42.Location" type="System.Drawing.Point, System.Drawing">
+    <value>451, 283</value>
   </data>
-  <data name="groupBox2.Location" type="System.Drawing.Point, System.Drawing">
-    <value>433, 181</value>
+  <data name="label42.Size" type="System.Drawing.Size, System.Drawing">
+    <value>42, 13</value>
   </data>
-  <data name="groupBox2.Size" type="System.Drawing.Size, System.Drawing">
-    <value>169, 78</value>
+  <data name="label42.TabIndex" type="System.Int32, mscorlib">
+    <value>132</value>
   </data>
-  <data name="groupBox2.TabIndex" type="System.Int32, mscorlib">
-    <value>130</value>
+  <data name="label42.Text" xml:space="preserve">
+    <value>Rudder</value>
   </data>
-  <data name="&gt;&gt;groupBox2.Name" xml:space="preserve">
-    <value>groupBox2</value>
+  <data name="&gt;&gt;label42.Name" xml:space="preserve">
+    <value>label42</value>
   </data>
-  <data name="&gt;&gt;groupBox2.Type" xml:space="preserve">
-    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  <data name="&gt;&gt;label42.Type" xml:space="preserve">
+    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
   </data>
-  <data name="&gt;&gt;groupBox2.Parent" xml:space="preserve">
+  <data name="&gt;&gt;label42.Parent" xml:space="preserve">
     <value>tabHeli</value>
   </data>
-  <data name="&gt;&gt;groupBox2.ZOrder" xml:space="preserve">
-    <value>7</value>
+  <data name="&gt;&gt;label42.ZOrder" xml:space="preserve">
+    <value>6</value>
   </data>
   <data name="label24.AutoSize" type="System.Boolean, mscorlib">
     <value>True</value>
@@ -4879,98 +3211,26 @@ will work with hexa's etc</value>
   <data name="&gt;&gt;label40.ZOrder" xml:space="preserve">
     <value>3</value>
   </data>
-  <data name="&gt;&gt;label41.Name" xml:space="preserve">
-    <value>label41</value>
-  </data>
-  <data name="&gt;&gt;label41.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label41.Parent" xml:space="preserve">
-    <value>groupBox1</value>
-  </data>
-  <data name="&gt;&gt;label41.ZOrder" xml:space="preserve">
-    <value>0</value>
-  </data>
-  <data name="&gt;&gt;label21.Name" xml:space="preserve">
-    <value>label21</value>
-  </data>
-  <data name="&gt;&gt;label21.Type" xml:space="preserve">
-    <value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;label21.Parent" xml:space="preserve">
-    <value>groupBox1</value>
-  </data>
-  <data name="&gt;&gt;label21.ZOrder" xml:space="preserve">
-    <value>1</value>
-  </data>
-  <data name="&gt;&gt;COL_MIN.Name" xml:space="preserve">
-    <value>COL_MIN</value>
-  </data>
-  <data name="&gt;&gt;COL_MIN.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;COL_MIN.Parent" xml:space="preserve">
-    <value>groupBox1</value>
-  </data>
-  <data name="&gt;&gt;COL_MIN.ZOrder" xml:space="preserve">
-    <value>2</value>
-  </data>
-  <data name="&gt;&gt;COL_MID.Name" xml:space="preserve">
-    <value>COL_MID</value>
-  </data>
-  <data name="&gt;&gt;COL_MID.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;COL_MID.Parent" xml:space="preserve">
-    <value>groupBox1</value>
-  </data>
-  <data name="&gt;&gt;COL_MID.ZOrder" xml:space="preserve">
-    <value>3</value>
-  </data>
-  <data name="&gt;&gt;COL_MAX.Name" xml:space="preserve">
-    <value>COL_MAX</value>
-  </data>
-  <data name="&gt;&gt;COL_MAX.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
-  </data>
-  <data name="&gt;&gt;COL_MAX.Parent" xml:space="preserve">
-    <value>groupBox1</value>
-  </data>
-  <data name="&gt;&gt;COL_MAX.ZOrder" xml:space="preserve">
-    <value>4</value>
-  </data>
-  <data name="&gt;&gt;BUT_0collective.Name" xml:space="preserve">
-    <value>BUT_0collective</value>
-  </data>
-  <data name="&gt;&gt;BUT_0collective.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
-  </data>
-  <data name="&gt;&gt;BUT_0collective.Parent" xml:space="preserve">
-    <value>groupBox1</value>
-  </data>
-  <data name="&gt;&gt;BUT_0collective.ZOrder" xml:space="preserve">
-    <value>5</value>
-  </data>
-  <data name="groupBox1.Location" type="System.Drawing.Point, System.Drawing">
-    <value>293, 90</value>
+  <data name="groupBox2.Location" type="System.Drawing.Point, System.Drawing">
+    <value>433, 181</value>
   </data>
-  <data name="groupBox1.Size" type="System.Drawing.Size, System.Drawing">
-    <value>80, 209</value>
+  <data name="groupBox2.Size" type="System.Drawing.Size, System.Drawing">
+    <value>169, 78</value>
   </data>
-  <data name="groupBox1.TabIndex" type="System.Int32, mscorlib">
-    <value>129</value>
+  <data name="groupBox2.TabIndex" type="System.Int32, mscorlib">
+    <value>130</value>
   </data>
-  <data name="&gt;&gt;groupBox1.Name" xml:space="preserve">
-    <value>groupBox1</value>
+  <data name="&gt;&gt;groupBox2.Name" xml:space="preserve">
+    <value>groupBox2</value>
   </data>
-  <data name="&gt;&gt;groupBox1.Type" xml:space="preserve">
+  <data name="&gt;&gt;groupBox2.Type" xml:space="preserve">
     <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
   </data>
-  <data name="&gt;&gt;groupBox1.Parent" xml:space="preserve">
+  <data name="&gt;&gt;groupBox2.Parent" xml:space="preserve">
     <value>tabHeli</value>
   </data>
-  <data name="&gt;&gt;groupBox1.ZOrder" xml:space="preserve">
-    <value>8</value>
+  <data name="&gt;&gt;groupBox2.ZOrder" xml:space="preserve">
+    <value>7</value>
   </data>
   <data name="label41.AutoSize" type="System.Boolean, mscorlib">
     <value>True</value>
@@ -5143,6 +3403,27 @@ will work with hexa's etc</value>
   <data name="&gt;&gt;BUT_0collective.ZOrder" xml:space="preserve">
     <value>5</value>
   </data>
+  <data name="groupBox1.Location" type="System.Drawing.Point, System.Drawing">
+    <value>293, 90</value>
+  </data>
+  <data name="groupBox1.Size" type="System.Drawing.Size, System.Drawing">
+    <value>80, 209</value>
+  </data>
+  <data name="groupBox1.TabIndex" type="System.Int32, mscorlib">
+    <value>129</value>
+  </data>
+  <data name="&gt;&gt;groupBox1.Name" xml:space="preserve">
+    <value>groupBox1</value>
+  </data>
+  <data name="&gt;&gt;groupBox1.Type" xml:space="preserve">
+    <value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;groupBox1.Parent" xml:space="preserve">
+    <value>tabHeli</value>
+  </data>
+  <data name="&gt;&gt;groupBox1.ZOrder" xml:space="preserve">
+    <value>8</value>
+  </data>
   <data name="HS4_TRIM.Location" type="System.Drawing.Point, System.Drawing">
     <value>535, 279</value>
   </data>
@@ -5887,35 +4168,53 @@ will work with hexa's etc</value>
   <data name="&gt;&gt;Gservoloc.ZOrder" xml:space="preserve">
     <value>36</value>
   </data>
-  <data name="&gt;&gt;BUT_reset.Name" xml:space="preserve">
-    <value>BUT_reset</value>
+  <data name="tabHeli.Location" type="System.Drawing.Point, System.Drawing">
+    <value>4, 22</value>
   </data>
-  <data name="&gt;&gt;BUT_reset.Type" xml:space="preserve">
-    <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
+  <data name="tabHeli.Size" type="System.Drawing.Size, System.Drawing">
+    <value>666, 393</value>
   </data>
-  <data name="&gt;&gt;BUT_reset.Parent" xml:space="preserve">
-    <value>tabReset</value>
+  <data name="tabHeli.TabIndex" type="System.Int32, mscorlib">
+    <value>5</value>
   </data>
-  <data name="&gt;&gt;BUT_reset.ZOrder" xml:space="preserve">
-    <value>0</value>
+  <data name="tabHeli.Text" xml:space="preserve">
+    <value>AC2 Heli</value>
   </data>
-  <data name="tabReset.Location" type="System.Drawing.Point, System.Drawing">
-    <value>4, 22</value>
+  <data name="&gt;&gt;tabHeli.Name" xml:space="preserve">
+    <value>tabHeli</value>
   </data>
-  <data name="tabReset.Size" type="System.Drawing.Size, System.Drawing">
-    <value>666, 393</value>
+  <data name="&gt;&gt;tabHeli.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
   </data>
-  <data name="tabReset.TabIndex" type="System.Int32, mscorlib">
-    <value>4</value>
+  <data name="&gt;&gt;tabHeli.Parent" xml:space="preserve">
+    <value>Tabs</value>
   </data>
-  <data name="tabReset.Text" xml:space="preserve">
-    <value>Reset</value>
+  <data name="&gt;&gt;tabHeli.ZOrder" xml:space="preserve">
+    <value>6</value>
   </data>
-  <data name="&gt;&gt;tabReset.Name" xml:space="preserve">
-    <value>tabReset</value>
+  <data name="Tabs.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
+    <value>Fill</value>
   </data>
-  <data name="&gt;&gt;tabReset.Type" xml:space="preserve">
-    <value>System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  <data name="Tabs.Location" type="System.Drawing.Point, System.Drawing">
+    <value>0, 0</value>
+  </data>
+  <data name="Tabs.Size" type="System.Drawing.Size, System.Drawing">
+    <value>674, 419</value>
+  </data>
+  <data name="Tabs.TabIndex" type="System.Int32, mscorlib">
+    <value>93</value>
+  </data>
+  <data name="&gt;&gt;Tabs.Name" xml:space="preserve">
+    <value>Tabs</value>
+  </data>
+  <data name="&gt;&gt;Tabs.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
+  <data name="&gt;&gt;Tabs.Parent" xml:space="preserve">
+    <value>$this</value>
+  </data>
+  <data name="&gt;&gt;Tabs.ZOrder" xml:space="preserve">
+    <value>0</value>
   </data>
   <data name="BUT_reset.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
     <value>NoControl</value>
@@ -5944,6 +4243,24 @@ will work with hexa's etc</value>
   <data name="&gt;&gt;BUT_reset.ZOrder" xml:space="preserve">
     <value>0</value>
   </data>
+  <data name="tabReset.Location" type="System.Drawing.Point, System.Drawing">
+    <value>4, 22</value>
+  </data>
+  <data name="tabReset.Size" type="System.Drawing.Size, System.Drawing">
+    <value>666, 393</value>
+  </data>
+  <data name="tabReset.TabIndex" type="System.Int32, mscorlib">
+    <value>4</value>
+  </data>
+  <data name="tabReset.Text" xml:space="preserve">
+    <value>Reset</value>
+  </data>
+  <data name="&gt;&gt;tabReset.Name" xml:space="preserve">
+    <value>tabReset</value>
+  </data>
+  <data name="&gt;&gt;tabReset.Type" xml:space="preserve">
+    <value>System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+  </data>
   <metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
     <value>True</value>
   </metadata>
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/.gitignore b/Tools/ArdupilotMegaPlanner/bin/Release/.gitignore
index 7ddb7730c77e4ce5e3ef87679be0104232a24485..de16b06a7a9e999c1b216d891d6459f4883c6a55 100644
--- a/Tools/ArdupilotMegaPlanner/bin/Release/.gitignore
+++ b/Tools/ArdupilotMegaPlanner/bin/Release/.gitignore
@@ -1,3 +1,4 @@
 *.pdb
 *.etag
-*.new
\ No newline at end of file
+*.new
+*.log
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb
index 3a1d3667b732364a3e9553cabf75239267dafc1b..e4daac93faaa9b707a08722f3655434779c996f1 100644
Binary files a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb and b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb differ
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/Driver/Arduino MEGA 2560.inf b/Tools/ArdupilotMegaPlanner/bin/Release/Driver/Arduino MEGA 2560.inf
new file mode 100644
index 0000000000000000000000000000000000000000..7053f3b95f9f6863f3ed36c2238f334783e2ff99
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/bin/Release/Driver/Arduino MEGA 2560.inf	
@@ -0,0 +1,106 @@
+;************************************************************
+; Windows USB CDC ACM Setup File
+; Copyright (c) 2000 Microsoft Corporation
+
+
+[Version]
+Signature="$Windows NT$"
+Class=Ports
+ClassGuid={4D36E978-E325-11CE-BFC1-08002BE10318}
+Provider=%MFGNAME%
+LayoutFile=layout.inf
+CatalogFile=%MFGFILENAME%.cat
+DriverVer=11/15/2007,5.1.2600.0
+
+[Manufacturer]
+%MFGNAME%=DeviceList, NTamd64
+
+[DestinationDirs]
+DefaultDestDir=12
+
+
+;------------------------------------------------------------------------------
+;  Windows 2000/XP/Vista-32bit Sections
+;------------------------------------------------------------------------------
+
+[DriverInstall.nt]
+include=mdmcpq.inf
+CopyFiles=DriverCopyFiles.nt
+AddReg=DriverInstall.nt.AddReg
+
+[DriverCopyFiles.nt]
+usbser.sys,,,0x20
+
+[DriverInstall.nt.AddReg]
+HKR,,DevLoader,,*ntkern
+HKR,,NTMPDriver,,%DRIVERFILENAME%.sys
+HKR,,EnumPropPages32,,"MsPorts.dll,SerialPortPropPageProvider"
+
+[DriverInstall.nt.Services]
+AddService=usbser, 0x00000002, DriverService.nt
+
+[DriverService.nt]
+DisplayName=%SERVICE%
+ServiceType=1
+StartType=3
+ErrorControl=1
+ServiceBinary=%12%\%DRIVERFILENAME%.sys
+
+;------------------------------------------------------------------------------
+;  Vista-64bit Sections
+;------------------------------------------------------------------------------
+
+[DriverInstall.NTamd64]
+include=mdmcpq.inf
+CopyFiles=DriverCopyFiles.NTamd64
+AddReg=DriverInstall.NTamd64.AddReg
+
+[DriverCopyFiles.NTamd64]
+%DRIVERFILENAME%.sys,,,0x20
+
+[DriverInstall.NTamd64.AddReg]
+HKR,,DevLoader,,*ntkern
+HKR,,NTMPDriver,,%DRIVERFILENAME%.sys
+HKR,,EnumPropPages32,,"MsPorts.dll,SerialPortPropPageProvider"
+
+[DriverInstall.NTamd64.Services]
+AddService=usbser, 0x00000002, DriverService.NTamd64
+
+[DriverService.NTamd64]
+DisplayName=%SERVICE%
+ServiceType=1
+StartType=3
+ErrorControl=1
+ServiceBinary=%12%\%DRIVERFILENAME%.sys
+
+
+;------------------------------------------------------------------------------
+;  Vendor and Product ID Definitions
+;------------------------------------------------------------------------------
+; When developing your USB device, the VID and PID used in the PC side
+; application program and the firmware on the microcontroller must match.
+; Modify the below line to use your VID and PID.  Use the format as shown below.
+; Note: One INF file can be used for multiple devices with different VID and PIDs.
+; For each supported device, append ",USB\VID_xxxx&PID_yyyy" to the end of the line.
+;------------------------------------------------------------------------------
+[SourceDisksFiles]
+[SourceDisksNames]
+[DeviceList]
+%DESCRIPTION%=DriverInstall, USB\VID_2341&PID_0010
+
+[DeviceList.NTamd64]
+%DESCRIPTION%=DriverInstall, USB\VID_2341&PID_0010
+
+
+;------------------------------------------------------------------------------
+;  String Definitions
+;------------------------------------------------------------------------------
+;Modify these strings to customize your device
+;------------------------------------------------------------------------------
+[Strings]
+MFGFILENAME="CDC_vista"
+DRIVERFILENAME ="usbser"
+MFGNAME="Arduino LLC (www.arduino.cc)"
+INSTDISK="Arduino Mega 2560 Driver Installer"
+DESCRIPTION="Arduino Mega 2560"
+SERVICE="USB RS-232 Emulation Driver"
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/Rascal/Rascal.xml b/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/Rascal/Rascal.xml
index 2e2813a25b2e6d9e97c631b2242aabb677c22a3a..bf4321ee12aca25f30b17e7d16772b7988f6fab4 100644
--- a/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/Rascal/Rascal.xml
+++ b/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/Rascal/Rascal.xml
@@ -86,7 +86,7 @@
             <location unit="IN">
                 <x> 68.9 </x>
                 <y> 0 </y>
-                <z> -3 </z>
+                <z> -13.1 </z>
             </location>
             <static_friction> 8.0 </static_friction>
             <dynamic_friction> 5.0 </dynamic_friction>
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/placeholder.txt b/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/placeholder.txt
new file mode 100644
index 0000000000000000000000000000000000000000..40816a2b5a97541edb85548945f5da2784a956ff
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/placeholder.txt
@@ -0,0 +1 @@
+Hi
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/version.txt b/Tools/ArdupilotMegaPlanner/bin/Release/version.txt
new file mode 100644
index 0000000000000000000000000000000000000000..e54e3f6834f610bbba55759cdfa543c51ce3209d
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/bin/Release/version.txt
@@ -0,0 +1 @@
+1.1.4482.15190
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/paramcompare.cs b/Tools/ArdupilotMegaPlanner/paramcompare.cs
index 99ef5a697615267b0294fb70f37cecf953096a8e..6671d1dce676feb8e8750cbd8ecb3b5ef39a9b85 100644
--- a/Tools/ArdupilotMegaPlanner/paramcompare.cs
+++ b/Tools/ArdupilotMegaPlanner/paramcompare.cs
@@ -11,16 +11,16 @@ namespace ArdupilotMega
 {
     public partial class ParamCompare : Form
     {
-        GCSViews.Configuration config;
+        DataGridView dgv;
         Hashtable param = new Hashtable();
         Hashtable param2 = new Hashtable();
 
-        public ParamCompare(GCSViews.Configuration config, Hashtable param, Hashtable param2)
+        public ParamCompare(DataGridView dgv, Hashtable param, Hashtable param2)
         {
             InitializeComponent();
             this.param = param;
             this.param2 = param2;
-            this.config = config;
+            this.dgv = dgv;
 
             processToScreen();
         }
@@ -61,7 +61,14 @@ namespace ArdupilotMega
             {
                 if ((bool)row.Cells[Use.Index].Value == true)
                 {
-                    config.EEPROM_View_float_TextChanged(new Control() { Name = row.Cells[Command.Index].Value.ToString(), Text = row.Cells[newvalue.Index].Value.ToString() }, null);
+                    foreach (DataGridViewRow dgvr in dgv.Rows)
+                    {
+                        if (dgvr.Cells[0].Value.ToString() == row.Cells[Command.Index].Value.ToString())
+                        {
+                            dgvr.Cells[1].Value = row.Cells[newvalue.Index].Value.ToString();
+                            break;
+                        }
+                    }
                 }
             }
             this.Close();
diff --git a/Tools/ArdupilotMegaPlanner/srtm.cs b/Tools/ArdupilotMegaPlanner/srtm.cs
index 7583ab71c3c743f79758761736899082343e3e6c..3a860c37eeb4a66494ea42c0bc68786c213f5e13 100644
--- a/Tools/ArdupilotMegaPlanner/srtm.cs
+++ b/Tools/ArdupilotMegaPlanner/srtm.cs
@@ -24,6 +24,9 @@ namespace ArdupilotMega
 
         public static int getAltitude(double lat, double lng, double zoom)
         {
+            if (!Directory.Exists(datadirectory))
+                Directory.CreateDirectory(datadirectory);
+
             short alt = 0;
 
             lat += 0.00083333333333333;
diff --git a/Tools/ArdupilotMegaPlanner/temp.Designer.cs b/Tools/ArdupilotMegaPlanner/temp.Designer.cs
index ec582ef476a5ae8ceb61e7bbfb6647b7274b5dcc..767443ebc44368746d1461e69fdd913df24fe8a2 100644
--- a/Tools/ArdupilotMegaPlanner/temp.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/temp.Designer.cs
@@ -198,7 +198,7 @@
             // 
             // BUT_lang_edit
             // 
-            this.BUT_lang_edit.Location = new System.Drawing.Point(365, 164);
+            this.BUT_lang_edit.Location = new System.Drawing.Point(323, 164);
             this.BUT_lang_edit.Name = "BUT_lang_edit";
             this.BUT_lang_edit.Size = new System.Drawing.Size(75, 23);
             this.BUT_lang_edit.TabIndex = 16;
@@ -208,7 +208,7 @@
             // 
             // BUT_georefimage
             // 
-            this.BUT_georefimage.Location = new System.Drawing.Point(263, 164);
+            this.BUT_georefimage.Location = new System.Drawing.Point(221, 164);
             this.BUT_georefimage.Name = "BUT_georefimage";
             this.BUT_georefimage.Size = new System.Drawing.Size(96, 23);
             this.BUT_georefimage.TabIndex = 0;
@@ -217,7 +217,7 @@
             // 
             // BUT_follow_me
             // 
-            this.BUT_follow_me.Location = new System.Drawing.Point(527, 164);
+            this.BUT_follow_me.Location = new System.Drawing.Point(485, 164);
             this.BUT_follow_me.Name = "BUT_follow_me";
             this.BUT_follow_me.Size = new System.Drawing.Size(75, 23);
             this.BUT_follow_me.TabIndex = 17;
@@ -227,7 +227,7 @@
             // 
             // BUT_ant_track
             // 
-            this.BUT_ant_track.Location = new System.Drawing.Point(446, 164);
+            this.BUT_ant_track.Location = new System.Drawing.Point(404, 164);
             this.BUT_ant_track.Name = "BUT_ant_track";
             this.BUT_ant_track.Size = new System.Drawing.Size(75, 23);
             this.BUT_ant_track.TabIndex = 18;
@@ -237,7 +237,7 @@
             // 
             // BUT_magcalib
             // 
-            this.BUT_magcalib.Location = new System.Drawing.Point(161, 164);
+            this.BUT_magcalib.Location = new System.Drawing.Point(119, 164);
             this.BUT_magcalib.Name = "BUT_magcalib";
             this.BUT_magcalib.Size = new System.Drawing.Size(96, 23);
             this.BUT_magcalib.TabIndex = 19;
diff --git a/Tools/ArdupilotMegaPlanner/temp.cs b/Tools/ArdupilotMegaPlanner/temp.cs
index fd5c9c8c08d66b43ec4d4d7208bfcddbe2a0d537..219e468aec1494758af7641678bde7e9e83903fa 100644
--- a/Tools/ArdupilotMegaPlanner/temp.cs
+++ b/Tools/ArdupilotMegaPlanner/temp.cs
@@ -15,10 +15,16 @@ using GMap.NET.WindowsForms;
 using GMap.NET.CacheProviders;
 using log4net;
 
+using System.Security.Permissions;
+
 namespace ArdupilotMega
 {
     public partial class temp : Form
     {
+        [DllImport("DIFXApi.dll", CharSet = CharSet.Unicode)]
+        public static extern Int32 DriverPackagePreinstall(string DriverPackageInfPath, Int32 Flags);
+
+
         private static readonly ILog log =
           LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
         public temp()
@@ -891,5 +897,13 @@ namespace ArdupilotMega
         {
             MagCalib.ProcessLog();
         }
+
+        void driverinstall()
+        {
+            int result = DriverPackagePreinstall(@"\Driver\XYZ.inf", 0);
+            if (result != 0)
+                MessageBox.Show("Driver installation failed.");
+
+        }
     }
 }
diff --git a/Tools/ArdupilotMegaPlanner/wix/Program.cs b/Tools/ArdupilotMegaPlanner/wix/Program.cs
new file mode 100644
index 0000000000000000000000000000000000000000..532beab2bc2eaa40b6bf4b5f73e0f3c1d0250b59
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/wix/Program.cs
@@ -0,0 +1,294 @@
+using System;
+using System.Collections.Generic;
+using System.Text;
+using System.IO;
+using System.Windows.Forms;
+using System.Diagnostics;
+using System.Runtime.InteropServices;
+
+namespace wix
+{
+    class Program
+    {
+        /// <summary>
+        /// The operation completed successfully.
+        /// </summary>
+        public const int ERROR_SUCCESS = 0;
+        /// <summary>
+        /// Incorrect function.
+        /// </summary>
+        public const int ERROR_INVALID_FUNCTION = 1;
+        /// <summary>
+        /// The system cannot find the file specified.
+        /// </summary>
+        public const int ERROR_FILE_NOT_FOUND = 2;
+        /// <summary>
+        /// The system cannot find the path specified.
+        /// </summary>
+        public const int ERROR_PATH_NOT_FOUND = 3;
+        /// <summary>
+        /// The system cannot open the file.
+        /// </summary>
+        public const int ERROR_TOO_MANY_OPEN_FILES = 4;
+        /// <summary>
+        /// Access is denied.
+        /// </summary>
+        public const int ERROR_ACCESS_DENIED = 5;
+
+        const Int32 DRIVER_PACKAGE_REPAIR = 0x00000001;
+        const Int32 DRIVER_PACKAGE_SILENT = 0x00000002;
+        const Int32 DRIVER_PACKAGE_FORCE = 0x00000004;
+        const Int32 DRIVER_PACKAGE_ONLY_IF_DEVICE_PRESENT = 0x00000008;
+        const Int32 DRIVER_PACKAGE_LEGACY_MODE = 0x00000010;
+        const Int32 DRIVER_PACKAGE_DELETE_FILES = 0x00000020;
+
+        [DllImport("DIFXApi.dll", CharSet = CharSet.Unicode)]
+        public static extern Int32 DriverPackagePreinstall(string DriverPackageInfPath, Int32 Flags);
+
+        static void driverinstall()
+        {
+            int result = DriverPackagePreinstall(@"..\Driver\Arduino MEGA 2560.inf", 0);
+            if (result != 0)
+                MessageBox.Show("Driver installation failed. " + result);
+
+        }
+
+        static int no = 0;
+
+        static StreamWriter sw;
+
+        static List<string> components = new List<string>();
+
+        static string mainexeid = "";
+
+        static void Main(string[] args)
+        {
+            if (args.Length == 0)
+            {
+                Console.WriteLine("Bad Directory");
+                return;
+            }
+
+            if (args[0] == "driver")
+            {
+                driverinstall();
+                return;
+            }
+
+            string path = args[0];
+
+            string file = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar+ "installer.wxs";
+
+            sw = new StreamWriter(file);
+
+            header();
+
+            sw.WriteLine("<Directory Id=\"APMPlanner\" Name=\"APM Planner\">");
+
+            sw.WriteLine(@"<Component Id=""InstallDirPermissions"" Guid=""{525389D7-EB3C-4d77-A5F6-A285CF99437D}"" KeyPath=""yes""> 
+                        <CreateFolder> 
+                            <Permission User=""Everyone"" GenericAll=""yes"" /> 
+                        </CreateFolder>
+                    </Component>");
+
+            //sw.WriteLine("<File Id=\"_" + no + "\" Source=\"" + file + "\" />");
+            
+
+            dodirectory(path, 0);
+
+
+            footer();
+
+            sw.Close();
+
+            /*
+            System.Diagnostics.Process P = new System.Diagnostics.Process();
+            P.StartInfo.FileName = "cmd.exe";
+                
+            P.StartInfo.Arguments =  " /c \"" + Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "installer.bat\"";
+            P.StartInfo.WorkingDirectory = Path.GetDirectoryName(Application.ExecutablePath);
+            P.Start();
+            */
+            //Console.ReadLine();
+        }
+
+        static void header()
+        {
+            string newid = System.Guid.NewGuid().ToString();
+
+            newid = "*";
+
+            StreamReader sr = new StreamReader(File.OpenRead("../Properties/AssemblyInfo.cs"));
+
+            string version = "0";
+
+            while (!sr.EndOfStream) {
+                string line = sr.ReadLine();
+                if (line.Contains("AssemblyFileVersion"))
+                {
+                    string[] items = line.Split(new char[] { '"' },StringSplitOptions.RemoveEmptyEntries);
+                    version = items[1];
+                    break;
+                }
+            }
+            sr.Close();
+
+            string data = @"<?xml version=""1.0"" encoding=""utf-8""?>
+<Wix xmlns=""http://schemas.microsoft.com/wix/2006/wi"" xmlns:netfx=""http://schemas.microsoft.com/wix/NetFxExtension"" xmlns:difx=""http://schemas.microsoft.com/wix/DifxAppExtension"">
+
+
+    <Product Id=""" + newid + @""" Name=""APM Planner"" Language=""1033"" Version="""+version+@""" Manufacturer=""Michael Oborne"" UpgradeCode=""{625389D7-EB3C-4d77-A5F6-A285CF99437D}"">
+
+        <Package Description=""APM Planner Installer"" Comments=""Apm Planner Installer"" Manufacturer=""Michael Oborne"" InstallerVersion=""200"" Compressed=""yes"" />
+
+
+<Upgrade Id=""{625389D7-EB3C-4d77-A5F6-A285CF99437D}"">
+    <UpgradeVersion OnlyDetect=""yes"" Minimum=""" + version + @""" Property=""NEWERVERSIONDETECTED"" IncludeMinimum=""no"" />
+    <UpgradeVersion OnlyDetect=""no"" Maximum=""" + version + @""" Property=""OLDERVERSIONBEINGUPGRADED"" IncludeMaximum=""no"" />
+</Upgrade>
+
+<InstallExecuteSequence>
+    <RemoveExistingProducts After=""InstallInitialize"" />
+</InstallExecuteSequence>
+
+        <PropertyRef Id=""NETFRAMEWORK35"" />
+
+        <Condition Message=""This application requires .NET Framework 3.5. Please install the .NET Framework then run this installer again.""><![CDATA[Installed OR NETFRAMEWORK35]]></Condition>
+
+        <Media Id=""1"" Cabinet=""product.cab"" EmbedCab=""yes"" />
+
+        <Directory Id=""TARGETDIR"" Name=""SourceDir"">
+            <Directory Id=""ProgramFilesFolder"" Name=""PFiles"">
+                ";
+
+            sw.WriteLine(data);
+        }
+
+        static void footer()
+        {
+            string data = @"
+                    
+                    <Directory Id=""drivers"" Name=""Drivers"">
+                        <Component Id=""MyDriver"" Guid=""{6AC8226E-A005-437e-A3CD-0FC32D9A346F}"">
+                            <File Id=""apm2inf""  Source=""..\Driver\Arduino MEGA 2560.inf"" />
+                            <difx:Driver AddRemovePrograms='no' Legacy=""yes"" PlugAndPlayPrompt=""no"" />
+                        </Component>
+                    </Directory>
+                </Directory>
+            </Directory>
+
+            <Directory Id=""ProgramMenuFolder"">
+                <Directory Id=""ApplicationProgramsFolder"" Name=""APM Planner"" />
+            </Directory>
+
+        </Directory>
+
+        <DirectoryRef Id=""ApplicationProgramsFolder"">
+            <Component Id=""ApplicationShortcut"" Guid=""{8BC628BA-08A0-43d6-88C8-D4C007AC4607}"">
+                <Shortcut Id=""ApplicationStartMenuShortcut"" Name=""APM Planner"" Description=""Ardupilot Mega Planner"" Target=""[APMPlanner]ArdupilotMegaPlanner.exe"" WorkingDirectory=""APMPlanner"" />
+                <RemoveFolder Id=""ApplicationProgramsFolder"" On=""uninstall"" />
+
+                <Shortcut Id=""UninstallProduct"" Name=""Uninstall APM Planner"" Description=""Uninstalls My Application"" Target=""[System64Folder]msiexec.exe"" Arguments=""/x [ProductCode]"" />
+
+
+
+                <RegistryValue Root=""HKCU"" Key=""Software\MichaelOborne\APMPlanner"" Name=""installed"" Type=""integer"" Value=""1"" KeyPath=""yes"" />
+
+
+
+
+            </Component>
+        </DirectoryRef>
+
+
+        <Feature Id=""MyFeature"" Title=""My 1st Feature"" Level=""1"">
+            <ComponentRef Id=""InstallDirPermissions"" />
+";
+            sw.WriteLine(data);
+
+            foreach (string comp in components)
+            {
+                sw.WriteLine(@"<ComponentRef Id="""+comp+@""" />");
+            }
+
+data = @"
+            
+            <ComponentRef Id=""ApplicationShortcut"" />
+            <ComponentRef Id=""MyDriver"" />
+        </Feature>
+
+        
+            <!-- Step 2: Add UI to your installer / Step 4: Trigger the custom action -->
+    <Property Id=""WIXUI_INSTALLDIR"" Value=""APMPlanner"" />
+
+    <UI>
+        <UIRef Id=""WixUI_InstallDir"" />
+        <Publish Dialog=""ExitDialog"" 
+            Control=""Finish"" 
+            Event=""DoAction"" 
+            Value=""LaunchApplication"">WIXUI_EXITDIALOGOPTIONALCHECKBOX = 1 and NOT Installed</Publish>
+    </UI>
+    <Property Id=""WIXUI_EXITDIALOGOPTIONALCHECKBOXTEXT"" Value=""Launch APM Planner"" />
+
+    <!-- Step 3: Include the custom action -->
+    <Property Id=""WixShellExecTarget"" Value=""[#" + mainexeid + @"]"" />
+    <CustomAction Id=""LaunchApplication"" 
+        BinaryKey=""WixCA"" 
+        DllEntry=""WixShellExec""
+        Impersonate=""yes"" />
+    </Product>
+    
+</Wix>";
+
+            sw.WriteLine(data);
+        }
+
+        static void dodirectory(string path, int level = 1)
+        {
+            string[] dirs = Directory.GetDirectories(path);
+
+            if (level != 0)
+                sw.WriteLine("<Directory Id=\"" + Path.GetFileName(path).Replace('-', '_') + no + "\" Name=\"" + Path.GetFileName(path) + "\">");
+
+            string[] files = Directory.GetFiles(path);
+
+            no++;
+
+            sw.WriteLine("<Component Id=\"_comp"+no+"\" Guid=\""+ System.Guid.NewGuid().ToString() +"\">");
+            components.Add("_comp"+no);
+
+            foreach (string filepath in files)
+            {
+                if (filepath.ToLower().EndsWith("release\\config.xml") || filepath.ToLower().Contains("ardupilotplanner.log") || filepath.ToLower().Contains("dataflash.bin") || filepath.ToLower().Contains(".etag"))
+                    continue;
+                no++;
+                sw.WriteLine("<File Id=\"_" + no + "\" Source=\"" + filepath + "\" />");
+
+                if (filepath.EndsWith("ArdupilotMegaPlanner.exe")) {
+                    mainexeid = "_" + no;
+                }
+            }
+
+            sw.WriteLine("</Component>");
+
+            foreach (string dir in dirs)
+            {
+                if (dir.EndsWith("gmapcache") || dir.EndsWith("srtm"))
+                    continue;
+                dodirectory(dir);
+            }
+
+            if (level != 0)
+                sw.WriteLine("</Directory>");
+        }
+
+        static string fixname(string name)
+        {
+            name = name.Replace("-", "_");
+            name = name.Replace(" ", "_");
+            name = name.Replace(" ", "_");
+
+            return name;
+        }
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/wix/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/wix/Properties/AssemblyInfo.cs
new file mode 100644
index 0000000000000000000000000000000000000000..145a4d08304c6466e1490a03ebb22d29ac2f7f75
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/wix/Properties/AssemblyInfo.cs
@@ -0,0 +1,36 @@
+using System.Reflection;
+using System.Runtime.CompilerServices;
+using System.Runtime.InteropServices;
+
+// General Information about an assembly is controlled through the following 
+// set of attributes. Change these attribute values to modify the information
+// associated with an assembly.
+[assembly: AssemblyTitle("wix")]
+[assembly: AssemblyDescription("")]
+[assembly: AssemblyConfiguration("")]
+[assembly: AssemblyCompany("")]
+[assembly: AssemblyProduct("wix")]
+[assembly: AssemblyCopyright("Copyright ©  2012")]
+[assembly: AssemblyTrademark("")]
+[assembly: AssemblyCulture("")]
+
+// Setting ComVisible to false makes the types in this assembly not visible 
+// to COM components.  If you need to access a type in this assembly from 
+// COM, set the ComVisible attribute to true on that type.
+[assembly: ComVisible(false)]
+
+// The following GUID is for the ID of the typelib if this project is exposed to COM
+[assembly: Guid("072e1c12-4a62-4be2-bcff-01fd33b14f95")]
+
+// Version information for an assembly consists of the following four values:
+//
+//      Major Version
+//      Minor Version 
+//      Build Number
+//      Revision
+//
+// You can specify all the values or you can default the Build and Revision Numbers 
+// by using the '*' as shown below:
+// [assembly: AssemblyVersion("1.0.*")]
+[assembly: AssemblyVersion("1.0.0.0")]
+[assembly: AssemblyFileVersion("1.0.0.0")]
diff --git a/Tools/ArdupilotMegaPlanner/wix/Properties/Resources.Designer.cs b/Tools/ArdupilotMegaPlanner/wix/Properties/Resources.Designer.cs
new file mode 100644
index 0000000000000000000000000000000000000000..8e668211f7fb9d0486b55cd8636f70c6a5585ec1
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/wix/Properties/Resources.Designer.cs
@@ -0,0 +1,63 @@
+//------------------------------------------------------------------------------
+// <auto-generated>
+//     This code was generated by a tool.
+//     Runtime Version:4.0.30319.261
+//
+//     Changes to this file may cause incorrect behavior and will be lost if
+//     the code is regenerated.
+// </auto-generated>
+//------------------------------------------------------------------------------
+
+namespace wix.Properties {
+    using System;
+    
+    
+    /// <summary>
+    ///   A strongly-typed resource class, for looking up localized strings, etc.
+    /// </summary>
+    // This class was auto-generated by the StronglyTypedResourceBuilder
+    // class via a tool like ResGen or Visual Studio.
+    // To add or remove a member, edit your .ResX file then rerun ResGen
+    // with the /str option, or rebuild your VS project.
+    [global::System.CodeDom.Compiler.GeneratedCodeAttribute("System.Resources.Tools.StronglyTypedResourceBuilder", "4.0.0.0")]
+    [global::System.Diagnostics.DebuggerNonUserCodeAttribute()]
+    [global::System.Runtime.CompilerServices.CompilerGeneratedAttribute()]
+    internal class Resources {
+        
+        private static global::System.Resources.ResourceManager resourceMan;
+        
+        private static global::System.Globalization.CultureInfo resourceCulture;
+        
+        [global::System.Diagnostics.CodeAnalysis.SuppressMessageAttribute("Microsoft.Performance", "CA1811:AvoidUncalledPrivateCode")]
+        internal Resources() {
+        }
+        
+        /// <summary>
+        ///   Returns the cached ResourceManager instance used by this class.
+        /// </summary>
+        [global::System.ComponentModel.EditorBrowsableAttribute(global::System.ComponentModel.EditorBrowsableState.Advanced)]
+        internal static global::System.Resources.ResourceManager ResourceManager {
+            get {
+                if (object.ReferenceEquals(resourceMan, null)) {
+                    global::System.Resources.ResourceManager temp = new global::System.Resources.ResourceManager("wix.Properties.Resources", typeof(Resources).Assembly);
+                    resourceMan = temp;
+                }
+                return resourceMan;
+            }
+        }
+        
+        /// <summary>
+        ///   Overrides the current thread's CurrentUICulture property for all
+        ///   resource lookups using this strongly typed resource class.
+        /// </summary>
+        [global::System.ComponentModel.EditorBrowsableAttribute(global::System.ComponentModel.EditorBrowsableState.Advanced)]
+        internal static global::System.Globalization.CultureInfo Culture {
+            get {
+                return resourceCulture;
+            }
+            set {
+                resourceCulture = value;
+            }
+        }
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/wix/Properties/Resources.resx b/Tools/ArdupilotMegaPlanner/wix/Properties/Resources.resx
new file mode 100644
index 0000000000000000000000000000000000000000..4fdb1b6aff69ba96d81420fab7a92b738c17f074
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/wix/Properties/Resources.resx
@@ -0,0 +1,101 @@
+<?xml version="1.0" encoding="utf-8"?>
+<root>
+	<!-- 
+		Microsoft ResX Schema
+
+		Version 1.3
+
+		The primary goals of this format is to allow a simple XML format 
+		that is mostly human readable. The generation and parsing of the 
+		various data types are done through the TypeConverter classes 
+		associated with the data types.
+
+		Example:
+
+		... ado.net/XML headers & schema ...
+		<resheader name="resmimetype">text/microsoft-resx</resheader>
+		<resheader name="version">1.3</resheader>
+		<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
+		<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
+		<data name="Name1">this is my long string</data>
+		<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
+		<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
+			[base64 mime encoded serialized .NET Framework object]
+		</data>
+		<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
+			[base64 mime encoded string representing a byte array form of the .NET Framework object]
+		</data>
+
+		There are any number of "resheader" rows that contain simple 
+		name/value pairs.
+
+		Each data row contains a name, and value. The row also contains a 
+		type or mimetype. Type corresponds to a .NET class that support 
+		text/value conversion through the TypeConverter architecture. 
+		Classes that don't support this are serialized and stored with the 
+		mimetype set.
+
+		The mimetype is used for serialized objects, and tells the 
+		ResXResourceReader how to depersist the object. This is currently not 
+		extensible. For a given mimetype the value must be set accordingly:
+
+		Note - application/x-microsoft.net.object.binary.base64 is the format 
+		that the ResXResourceWriter will generate, however the reader can 
+		read any of the formats listed below.
+
+		mimetype: application/x-microsoft.net.object.binary.base64
+		value   : The object must be serialized with 
+			: System.Serialization.Formatters.Binary.BinaryFormatter
+			: and then encoded with base64 encoding.
+
+		mimetype: application/x-microsoft.net.object.soap.base64
+		value   : The object must be serialized with 
+			: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
+			: and then encoded with base64 encoding.
+
+		mimetype: application/x-microsoft.net.object.bytearray.base64
+		value   : The object must be serialized into a byte array 
+			: using a System.ComponentModel.TypeConverter
+			: and then encoded with base64 encoding.
+	-->
+	
+	<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
+		<xsd:element name="root" msdata:IsDataSet="true">
+			<xsd:complexType>
+				<xsd:choice maxOccurs="unbounded">
+					<xsd:element name="data">
+						<xsd:complexType>
+							<xsd:sequence>
+								<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+								<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
+							</xsd:sequence>
+							<xsd:attribute name="name" type="xsd:string" msdata:Ordinal="1" />
+							<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
+							<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
+						</xsd:complexType>
+					</xsd:element>
+					<xsd:element name="resheader">
+						<xsd:complexType>
+							<xsd:sequence>
+								<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
+							</xsd:sequence>
+							<xsd:attribute name="name" type="xsd:string" use="required" />
+						</xsd:complexType>
+					</xsd:element>
+				</xsd:choice>
+			</xsd:complexType>
+		</xsd:element>
+	</xsd:schema>
+	<resheader name="resmimetype">
+		<value>text/microsoft-resx</value>
+	</resheader>
+	<resheader name="version">
+		<value>1.3</value>
+	</resheader>
+	<resheader name="reader">
+		<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.3500.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+	</resheader>
+	<resheader name="writer">
+		<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.3500.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
+	</resheader>
+</root>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/wix/Properties/Settings.Designer.cs b/Tools/ArdupilotMegaPlanner/wix/Properties/Settings.Designer.cs
new file mode 100644
index 0000000000000000000000000000000000000000..50ea81e4e8a72710b9e9713d3ed36159a8870a1c
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/wix/Properties/Settings.Designer.cs
@@ -0,0 +1,26 @@
+//------------------------------------------------------------------------------
+// <auto-generated>
+//     This code was generated by a tool.
+//     Runtime Version:4.0.30319.261
+//
+//     Changes to this file may cause incorrect behavior and will be lost if
+//     the code is regenerated.
+// </auto-generated>
+//------------------------------------------------------------------------------
+
+namespace wix.Properties {
+    
+    
+    [global::System.Runtime.CompilerServices.CompilerGeneratedAttribute()]
+    [global::System.CodeDom.Compiler.GeneratedCodeAttribute("Microsoft.VisualStudio.Editors.SettingsDesigner.SettingsSingleFileGenerator", "10.0.0.0")]
+    internal sealed partial class Settings : global::System.Configuration.ApplicationSettingsBase {
+        
+        private static Settings defaultInstance = ((Settings)(global::System.Configuration.ApplicationSettingsBase.Synchronized(new Settings())));
+        
+        public static Settings Default {
+            get {
+                return defaultInstance;
+            }
+        }
+    }
+}
diff --git a/Tools/ArdupilotMegaPlanner/wix/Properties/Settings.settings b/Tools/ArdupilotMegaPlanner/wix/Properties/Settings.settings
new file mode 100644
index 0000000000000000000000000000000000000000..049245f401462e7e3dfbb96385e122ca467a9dab
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/wix/Properties/Settings.settings
@@ -0,0 +1,6 @@
+<?xml version='1.0' encoding='utf-8'?>
+<SettingsFile xmlns="http://schemas.microsoft.com/VisualStudio/2004/01/settings" CurrentProfile="(Default)">
+  <Profiles>
+    <Profile Name="(Default)" />
+  </Profiles>
+</SettingsFile>
diff --git a/Tools/ArdupilotMegaPlanner/wix/Properties/app.manifest b/Tools/ArdupilotMegaPlanner/wix/Properties/app.manifest
new file mode 100644
index 0000000000000000000000000000000000000000..8948c3006cd6d282a561576d7da8432afab7eed2
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/wix/Properties/app.manifest
@@ -0,0 +1,47 @@
+<?xml version="1.0" encoding="utf-8"?>
+<asmv1:assembly manifestVersion="1.0" xmlns="urn:schemas-microsoft-com:asm.v1" xmlns:asmv1="urn:schemas-microsoft-com:asm.v1" xmlns:asmv2="urn:schemas-microsoft-com:asm.v2" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance">
+  <assemblyIdentity version="1.0.0.0" name="MyApplication.app" />
+  <trustInfo xmlns="urn:schemas-microsoft-com:asm.v2">
+    <security>
+      <requestedPrivileges xmlns="urn:schemas-microsoft-com:asm.v3">
+        <!-- UAC Manifest Options
+            If you want to change the Windows User Account Control level replace the 
+            requestedExecutionLevel node with one of the following.
+
+        <requestedExecutionLevel  level="asInvoker" uiAccess="false" />
+        <requestedExecutionLevel  level="requireAdministrator" uiAccess="false" />
+        <requestedExecutionLevel  level="highestAvailable" uiAccess="false" />
+
+            Specifying requestedExecutionLevel node will disable file and registry virtualization.
+            If you want to utilize File and Registry Virtualization for backward 
+            compatibility then delete the requestedExecutionLevel node.
+        -->
+        <requestedExecutionLevel level="requireAdministrator" uiAccess="false" />
+      </requestedPrivileges>
+      <applicationRequestMinimum>
+        <defaultAssemblyRequest permissionSetReference="Custom" />
+        <PermissionSet class="System.Security.PermissionSet" version="1" ID="Custom" SameSite="site" Unrestricted="true" />
+      </applicationRequestMinimum>
+    </security>
+  </trustInfo>
+  <compatibility xmlns="urn:schemas-microsoft-com:compatibility.v1">
+    <application>
+      <!-- A list of all Windows versions that this application is designed to work with. Windows will automatically select the most compatible environment.-->
+      <!-- If your application is designed to work with Windows 7, uncomment the following supportedOS node-->
+      <!--<supportedOS Id="{35138b9a-5d96-4fbd-8e2d-a2440225f93a}"/>-->
+    </application>
+  </compatibility>
+  <!-- Enable themes for Windows common controls and dialogs (Windows XP and later) -->
+  <!-- <dependency>
+    <dependentAssembly>
+      <assemblyIdentity
+          type="win32"
+          name="Microsoft.Windows.Common-Controls"
+          version="6.0.0.0"
+          processorArchitecture="*"
+          publicKeyToken="6595b64144ccf1df"
+          language="*"
+        />
+    </dependentAssembly>
+  </dependency>-->
+</asmv1:assembly>
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/wix/app.config b/Tools/ArdupilotMegaPlanner/wix/app.config
new file mode 100644
index 0000000000000000000000000000000000000000..e59af44de2ddb14170137575f1bb09790c6a877c
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/wix/app.config
@@ -0,0 +1,3 @@
+<?xml version="1.0"?>
+<configuration>
+<startup><supportedRuntime version="v2.0.50727"/></startup></configuration>
diff --git a/Tools/ArdupilotMegaPlanner/wix/wix.csproj b/Tools/ArdupilotMegaPlanner/wix/wix.csproj
new file mode 100644
index 0000000000000000000000000000000000000000..42fbee7ca3c2795c4abb183e6f05117458f3bf6c
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/wix/wix.csproj
@@ -0,0 +1,121 @@
+<?xml version="1.0" encoding="utf-8"?>
+<Project ToolsVersion="4.0" DefaultTargets="Build" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
+  <PropertyGroup>
+    <Configuration Condition=" '$(Configuration)' == '' ">Debug</Configuration>
+    <Platform Condition=" '$(Platform)' == '' ">x86</Platform>
+    <ProductVersion>8.0.30703</ProductVersion>
+    <SchemaVersion>2.0</SchemaVersion>
+    <ProjectGuid>{76374F95-C343-4ACC-B86F-7ECFDD668F46}</ProjectGuid>
+    <OutputType>Exe</OutputType>
+    <AppDesignerFolder>Properties</AppDesignerFolder>
+    <RootNamespace>wix</RootNamespace>
+    <AssemblyName>wix</AssemblyName>
+    <TargetFrameworkVersion>v3.5</TargetFrameworkVersion>
+    <TargetFrameworkProfile>
+    </TargetFrameworkProfile>
+    <FileAlignment>512</FileAlignment>
+    <IsWebBootstrapper>false</IsWebBootstrapper>
+    <PublishUrl>publish\</PublishUrl>
+    <Install>true</Install>
+    <InstallFrom>Disk</InstallFrom>
+    <UpdateEnabled>false</UpdateEnabled>
+    <UpdateMode>Foreground</UpdateMode>
+    <UpdateInterval>7</UpdateInterval>
+    <UpdateIntervalUnits>Days</UpdateIntervalUnits>
+    <UpdatePeriodically>false</UpdatePeriodically>
+    <UpdateRequired>false</UpdateRequired>
+    <MapFileExtensions>true</MapFileExtensions>
+    <ApplicationRevision>0</ApplicationRevision>
+    <ApplicationVersion>1.0.0.%2a</ApplicationVersion>
+    <UseApplicationTrust>false</UseApplicationTrust>
+    <BootstrapperEnabled>true</BootstrapperEnabled>
+  </PropertyGroup>
+  <PropertyGroup Condition=" '$(Configuration)|$(Platform)' == 'Debug|x86' ">
+    <PlatformTarget>x86</PlatformTarget>
+    <DebugSymbols>true</DebugSymbols>
+    <DebugType>full</DebugType>
+    <Optimize>false</Optimize>
+    <OutputPath>bin\Debug\</OutputPath>
+    <DefineConstants>DEBUG;TRACE</DefineConstants>
+    <ErrorReport>prompt</ErrorReport>
+    <WarningLevel>4</WarningLevel>
+  </PropertyGroup>
+  <PropertyGroup Condition=" '$(Configuration)|$(Platform)' == 'Release|x86' ">
+    <PlatformTarget>x86</PlatformTarget>
+    <DebugType>pdbonly</DebugType>
+    <Optimize>true</Optimize>
+    <OutputPath>..\Msi\</OutputPath>
+    <DefineConstants>DEBUG;TRACE</DefineConstants>
+    <ErrorReport>prompt</ErrorReport>
+    <WarningLevel>4</WarningLevel>
+  </PropertyGroup>
+  <PropertyGroup />
+  <PropertyGroup>
+    <TargetZone>LocalIntranet</TargetZone>
+  </PropertyGroup>
+  <PropertyGroup>
+    <GenerateManifests>false</GenerateManifests>
+  </PropertyGroup>
+  <PropertyGroup>
+    <ApplicationManifest>Properties\app.manifest</ApplicationManifest>
+  </PropertyGroup>
+  <ItemGroup>
+    <Reference Include="System" />
+    <Reference Include="System.Data" />
+    <Reference Include="System.Windows.Forms" />
+    <Reference Include="System.Xml" />
+  </ItemGroup>
+  <ItemGroup>
+    <Compile Include="Program.cs" />
+    <Compile Include="Properties\AssemblyInfo.cs" />
+    <Compile Include="Properties\Resources.Designer.cs">
+      <AutoGen>True</AutoGen>
+      <DesignTime>True</DesignTime>
+      <DependentUpon>Resources.resx</DependentUpon>
+    </Compile>
+    <Compile Include="Properties\Settings.Designer.cs">
+      <AutoGen>True</AutoGen>
+      <DesignTimeSharedInput>True</DesignTimeSharedInput>
+      <DependentUpon>Settings.settings</DependentUpon>
+    </Compile>
+  </ItemGroup>
+  <ItemGroup>
+    <None Include="app.config" />
+    <None Include="Properties\app.manifest" />
+    <None Include="Properties\Settings.settings">
+      <Generator>SettingsSingleFileGenerator</Generator>
+      <LastGenOutput>Settings.Designer.cs</LastGenOutput>
+    </None>
+  </ItemGroup>
+  <ItemGroup>
+    <BootstrapperPackage Include="Microsoft.Net.Client.3.5">
+      <Visible>False</Visible>
+      <ProductName>.NET Framework 3.5 SP1 Client Profile</ProductName>
+      <Install>false</Install>
+    </BootstrapperPackage>
+    <BootstrapperPackage Include="Microsoft.Net.Framework.3.5.SP1">
+      <Visible>False</Visible>
+      <ProductName>.NET Framework 3.5 SP1</ProductName>
+      <Install>true</Install>
+    </BootstrapperPackage>
+    <BootstrapperPackage Include="Microsoft.Windows.Installer.3.1">
+      <Visible>False</Visible>
+      <ProductName>Windows Installer 3.1</ProductName>
+      <Install>true</Install>
+    </BootstrapperPackage>
+  </ItemGroup>
+  <ItemGroup>
+    <EmbeddedResource Include="Properties\Resources.resx">
+      <Generator>ResXFileCodeGenerator</Generator>
+      <LastGenOutput>Resources.Designer.cs</LastGenOutput>
+    </EmbeddedResource>
+  </ItemGroup>
+  <Import Project="$(MSBuildToolsPath)\Microsoft.CSharp.targets" />
+  <!-- To modify your build process, add your task inside one of the targets below and uncomment it. 
+       Other similar extension points exist, see Microsoft.Common.targets.
+  <Target Name="BeforeBuild">
+  </Target>
+  <Target Name="AfterBuild">
+  </Target>
+  -->
+</Project>
\ No newline at end of file
diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py
index e64813ae26752b9321385c865c5ffbb2926badcc..fefd770cc8bc9286210d9036a8bc512d3e624edc 100644
--- a/Tools/autotest/arduplane.py
+++ b/Tools/autotest/arduplane.py
@@ -69,7 +69,7 @@ def fly_left_circuit(mavproxy, mav):
             return False
         mavproxy.send('rc 1 1500\n')
         print("Starting leg %u" % i)
-        if not wait_distance(mav, 100):
+        if not wait_distance(mav, 100, accuracy=20):
             return False
     print("Circuit complete")
     return True
@@ -289,7 +289,6 @@ def fly_ArduPlane(viewerip=None):
     try:
         mav.wait_heartbeat()
         setup_rc(mavproxy)
-        mavproxy.expect('APM: init home')
         mav.recv_match(type='GPS_RAW', condition='MAV.flightmode!="INITIALISING" and GPS_RAW.fix_type==2 and GPS_RAW.lat != 0 and GPS_RAW.alt != 0 and VFR_HUD.alt > 10',
                        blocking=True)
         homeloc = current_location(mav)
diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h
index 1cd685d557ca76563db0b2739e6d160ea2c40fc8..883c158a530a1830485c553ede66d7ece57bec3d 100644
--- a/libraries/AP_AHRS/AP_AHRS.h
+++ b/libraries/AP_AHRS/AP_AHRS.h
@@ -91,8 +91,8 @@ protected:
 
 	// note: we use ref-to-pointer here so that our caller can change the GPS without our noticing
 	//       IMU under us without our noticing.
-	GPS 		*&_gps;
 	IMU 		*_imu;
+	GPS 		*&_gps;
 
 	// true if we are doing centripetal acceleration correction
 	bool		_centripetal;
diff --git a/libraries/AP_Compass/Compass.cpp b/libraries/AP_Compass/Compass.cpp
index ef1181bdf5a057b53e1f206e3fbed821abf41507..ddbcf93f812b98b07c7f9f9fb62184b6c7a3e550 100644
--- a/libraries/AP_Compass/Compass.cpp
+++ b/libraries/AP_Compass/Compass.cpp
@@ -17,13 +17,13 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = {
 //
 Compass::Compass(void) :
 	product_id(AP_COMPASS_TYPE_UNKNOWN),
+    _orientation(ROTATION_NONE),
     _declination		(0.0),
     _learn(1),
     _use_for_yaw(1),
-    _null_enable(false),
-    _null_init_done(false),
     _auto_declination(1),
-    _orientation(ROTATION_NONE)
+    _null_enable(false),
+    _null_init_done(false)
 {
 }
 
diff --git a/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde b/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde
index ab9a0b3721553b37ac3a6245a14fedc351281635..9de621e309c82df2501aa05bf98f2e47cf45a079 100644
--- a/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde
+++ b/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde
@@ -9,6 +9,7 @@
 #include <FastSerial.h>
 #include <AP_Common.h>
 #include <AP_GPS.h>
+#include <AP_Math.h>
 
 FastSerialPort0(Serial);
 FastSerialPort1(Serial1);
diff --git a/libraries/AP_Motors/AP_Motors.h b/libraries/AP_Motors/AP_Motors.h
index 1d5f9e718466f2795a6baf3e5167ae8c3f7783af..cf936f469b36a24cebe0d23599ed2906145ceb14 100644
--- a/libraries/AP_Motors/AP_Motors.h
+++ b/libraries/AP_Motors/AP_Motors.h
@@ -79,12 +79,12 @@ public:
 
 	// arm, disarm or check status status of motors
 	virtual bool armed() { return _armed; };
-	virtual void armed(bool armed) { _armed = armed; };
+	virtual void armed(bool arm) { _armed = arm; };
 
 	// check or set status of auto_armed - controls whether autopilot can take control of throttle
 	// Note: this should probably be moved out of this class as it has little to do with the motors
 	virtual bool auto_armed() { return _auto_armed; };
-	virtual void auto_armed(bool armed) { _auto_armed = armed; };
+	virtual void auto_armed(bool arm) { _auto_armed = arm; };
 
 	// set_min_throttle - sets the minimum throttle that will be sent to the engines when they're not off (i.e. to prevents issues with some motors spinning and some not at very low throttle)
 	virtual void set_min_throttle(uint16_t min_throttle) { _min_throttle = min_throttle; };
diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h
index 9ad39d9c5924fec8e1c97fcc0e68576a9164dfdd..3d3b162a737c0a90aae2e0f95980c6653e546d45 100644
--- a/libraries/AP_Motors/AP_MotorsHeli.h
+++ b/libraries/AP_Motors/AP_MotorsHeli.h
@@ -95,7 +95,7 @@ public:
 	virtual void init_swash();
 
 	// heli_move_swash - moves swash plate to attitude of parameters passed in
-	virtual void move_swash(int roll_out, int pitch_out, int coll_out, int yaw_out);
+	virtual void move_swash(int16_t roll_out, int16_t pitch_out, int16_t coll_out, int16_t yaw_out);
 
 	// var_info for holding Parameter information
 	static const struct AP_Param::GroupInfo var_info[];
diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp
index 851f06365b0ab104b026541706e9a188738db84b..93944d1e372ea08f3ff4f030eb358900ca6b07ab 100644
--- a/libraries/AP_Motors/AP_MotorsMatrix.cpp
+++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp
@@ -101,7 +101,7 @@ void AP_MotorsMatrix::output_min()
 	int8_t i;
 
 	// fill the motor_out[] array for HIL use and send minimum value to each motor
-	for( int8_t i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
+	for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
 		if( motor_enabled[i] ) {
 			motor_out[i] = _rc_throttle->radio_min;
 			_rc->OutputCh(_motor_to_channel_map[i], motor_out[i]);
@@ -146,14 +146,14 @@ void AP_MotorsMatrix::output_armed()
 							_rc_pitch->pwm_out * _pitch_factor[i] +
 							_rc_yaw->pwm_out*_yaw_factor[i];
 		}
-		// ensure motor is not below the minimum
-		motor_out[AP_MOTORS_MOT_1]	= max(motor_out[AP_MOTORS_MOT_1], 	out_min);
 	}
 
 	// stability patch
 	for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
-		if( motor_enabled[i] && opposite_motor[i] != AP_MOTORS_MATRIX_MOTOR_UNDEFINED && motor_out[i] > out_max ) {
-			motor_out[opposite_motor[i]] -= motor_out[i] - out_max;
+		if( motor_enabled[i] && motor_out[i] > out_max ) {
+			if( opposite_motor[i] != AP_MOTORS_MATRIX_MOTOR_UNDEFINED ) {
+				motor_out[opposite_motor[i]] -= motor_out[i] - out_max;
+			}
 			motor_out[i] = out_max;
 		}
 	}
diff --git a/libraries/AP_Motors/AP_MotorsMatrix.h b/libraries/AP_Motors/AP_MotorsMatrix.h
index 758ebff738c2bd932b2399f50cc0b3c3edd8d464..0384ccf3ed274e20df3c961ce8c2b5a3033da11a 100644
--- a/libraries/AP_Motors/AP_MotorsMatrix.h
+++ b/libraries/AP_Motors/AP_MotorsMatrix.h
@@ -66,8 +66,6 @@ public:
 	virtual void setup_motors() { remove_all_motors(); };
 
 	// matrix
-	AP_Int16	angle[AP_MOTORS_MAX_NUM_MOTORS];			// angle in degrees from the front of the copter
-	AP_Int8		direction[AP_MOTORS_MAX_NUM_MOTORS];		// direction of rotation of the motor (-1 = clockwise, +1 = counter clockwise)
 	AP_Int8		opposite_motor[AP_MOTORS_MAX_NUM_MOTORS];	// motor number of the opposite motor
 	AP_Int8		test_order[AP_MOTORS_MAX_NUM_MOTORS];		// order of the motors in the test sequence
 
diff --git a/libraries/AP_Motors/AP_MotorsOcta.cpp b/libraries/AP_Motors/AP_MotorsOcta.cpp
index 33c16963d3d19d1dd879d32fdd5b06eb8ede031e..f50be046808100901e33bd30516c164ab1445f03 100644
--- a/libraries/AP_Motors/AP_MotorsOcta.cpp
+++ b/libraries/AP_Motors/AP_MotorsOcta.cpp
@@ -33,7 +33,7 @@ void AP_MotorsOcta::setup_motors()
 		add_motor_raw(AP_MOTORS_MOT_1,  1.0,  0.34, AP_MOTORS_MATRIX_MOTOR_CW,  AP_MOTORS_MOT_2, 7);
 		add_motor_raw(AP_MOTORS_MOT_2, -1.0, -0.32, AP_MOTORS_MATRIX_MOTOR_CW,  AP_MOTORS_MOT_1, 3);
 		add_motor_raw(AP_MOTORS_MOT_3,  1.0, -0.32, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_6, 6);
-		add_motor_raw(AP_MOTORS_MOT_4, -0.5,  -1.0, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_5, 8);
+		add_motor_raw(AP_MOTORS_MOT_4, -0.5,  -1.0, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_5, 4);
 		add_motor_raw(AP_MOTORS_MOT_5,  1.0,   1.0, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_4, 8);
 		add_motor_raw(AP_MOTORS_MOT_6, -1.0,  0.34, AP_MOTORS_MATRIX_MOTOR_CCW, AP_MOTORS_MOT_3, 2);
 		add_motor_raw(AP_MOTORS_MOT_7, -1.0,   1.0, AP_MOTORS_MATRIX_MOTOR_CW,  AP_MOTORS_MOT_8, 1);
diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h b/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h
index 72ebba618dd0cc2df0d4ea6f00a31512801630f8..204c907555b2bcfc3469d6107346f483f4865c60 100644
--- a/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h
+++ b/libraries/GCS_MAVLink/include/ardupilotmega/ardupilotmega.h
@@ -16,7 +16,7 @@ extern "C" {
 #endif
 
 #ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 118, 242, 19, 97, 233, 0, 18, 68, 136, 127, 42, 21, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7}
+#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 118, 242, 19, 97, 233, 0, 18, 68, 136, 127, 42, 21, 93, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7}
 #endif
 
 #ifndef MAVLINK_MESSAGE_INFO
diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_radio.h b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_radio.h
index 1a403982011a3bbd3445b83634751b14ed2fa637..ee7e8f16cff35cb9eb759bec7c990bd648442eaf 100644
--- a/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_radio.h
+++ b/libraries/GCS_MAVLink/include/ardupilotmega/mavlink_msg_radio.h
@@ -7,8 +7,9 @@ typedef struct __mavlink_radio_t
  uint8_t rssi; ///< local signal strength
  uint8_t remrssi; ///< remote signal strength
  uint8_t txbuf; ///< how full the tx buffer is as a percentage
+ uint8_t noise; ///< background noise level
+ uint8_t remnoise; ///< remote background noise level
  uint16_t rxerrors; ///< receive errors
- uint16_t serrors; ///< serial errors
  uint16_t fixed; ///< count of error corrected packets
 } mavlink_radio_t;
 
@@ -19,12 +20,13 @@ typedef struct __mavlink_radio_t
 
 #define MAVLINK_MESSAGE_INFO_RADIO { \
 	"RADIO", \
-	6, \
+	7, \
 	{  { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_radio_t, rssi) }, \
          { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_radio_t, remrssi) }, \
          { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_radio_t, txbuf) }, \
-         { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_radio_t, rxerrors) }, \
-         { "serrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 5, offsetof(mavlink_radio_t, serrors) }, \
+         { "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_radio_t, noise) }, \
+         { "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_t, remnoise) }, \
+         { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 5, offsetof(mavlink_radio_t, rxerrors) }, \
          { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 7, offsetof(mavlink_radio_t, fixed) }, \
          } \
 }
@@ -39,21 +41,23 @@ typedef struct __mavlink_radio_t
  * @param rssi local signal strength
  * @param remrssi remote signal strength
  * @param txbuf how full the tx buffer is as a percentage
+ * @param noise background noise level
+ * @param remnoise remote background noise level
  * @param rxerrors receive errors
- * @param serrors serial errors
  * @param fixed count of error corrected packets
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-						       uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint16_t rxerrors, uint16_t serrors, uint16_t fixed)
+						       uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
 	char buf[9];
 	_mav_put_uint8_t(buf, 0, rssi);
 	_mav_put_uint8_t(buf, 1, remrssi);
 	_mav_put_uint8_t(buf, 2, txbuf);
-	_mav_put_uint16_t(buf, 3, rxerrors);
-	_mav_put_uint16_t(buf, 5, serrors);
+	_mav_put_uint8_t(buf, 3, noise);
+	_mav_put_uint8_t(buf, 4, remnoise);
+	_mav_put_uint16_t(buf, 5, rxerrors);
 	_mav_put_uint16_t(buf, 7, fixed);
 
         memcpy(_MAV_PAYLOAD(msg), buf, 9);
@@ -62,8 +66,9 @@ static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t compone
 	packet.rssi = rssi;
 	packet.remrssi = remrssi;
 	packet.txbuf = txbuf;
+	packet.noise = noise;
+	packet.remnoise = remnoise;
 	packet.rxerrors = rxerrors;
-	packet.serrors = serrors;
 	packet.fixed = fixed;
 
         memcpy(_MAV_PAYLOAD(msg), &packet, 9);
@@ -82,22 +87,24 @@ static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t compone
  * @param rssi local signal strength
  * @param remrssi remote signal strength
  * @param txbuf how full the tx buffer is as a percentage
+ * @param noise background noise level
+ * @param remnoise remote background noise level
  * @param rxerrors receive errors
- * @param serrors serial errors
  * @param fixed count of error corrected packets
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
 							   mavlink_message_t* msg,
-						           uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint16_t rxerrors,uint16_t serrors,uint16_t fixed)
+						           uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
 	char buf[9];
 	_mav_put_uint8_t(buf, 0, rssi);
 	_mav_put_uint8_t(buf, 1, remrssi);
 	_mav_put_uint8_t(buf, 2, txbuf);
-	_mav_put_uint16_t(buf, 3, rxerrors);
-	_mav_put_uint16_t(buf, 5, serrors);
+	_mav_put_uint8_t(buf, 3, noise);
+	_mav_put_uint8_t(buf, 4, remnoise);
+	_mav_put_uint16_t(buf, 5, rxerrors);
 	_mav_put_uint16_t(buf, 7, fixed);
 
         memcpy(_MAV_PAYLOAD(msg), buf, 9);
@@ -106,8 +113,9 @@ static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t co
 	packet.rssi = rssi;
 	packet.remrssi = remrssi;
 	packet.txbuf = txbuf;
+	packet.noise = noise;
+	packet.remnoise = remnoise;
 	packet.rxerrors = rxerrors;
-	packet.serrors = serrors;
 	packet.fixed = fixed;
 
         memcpy(_MAV_PAYLOAD(msg), &packet, 9);
@@ -127,7 +135,7 @@ static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t co
  */
 static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_t* radio)
 {
-	return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->rxerrors, radio->serrors, radio->fixed);
+	return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed);
 }
 
 /**
@@ -137,21 +145,23 @@ static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t compo
  * @param rssi local signal strength
  * @param remrssi remote signal strength
  * @param txbuf how full the tx buffer is as a percentage
+ * @param noise background noise level
+ * @param remnoise remote background noise level
  * @param rxerrors receive errors
- * @param serrors serial errors
  * @param fixed count of error corrected packets
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint16_t rxerrors, uint16_t serrors, uint16_t fixed)
+static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
 	char buf[9];
 	_mav_put_uint8_t(buf, 0, rssi);
 	_mav_put_uint8_t(buf, 1, remrssi);
 	_mav_put_uint8_t(buf, 2, txbuf);
-	_mav_put_uint16_t(buf, 3, rxerrors);
-	_mav_put_uint16_t(buf, 5, serrors);
+	_mav_put_uint8_t(buf, 3, noise);
+	_mav_put_uint8_t(buf, 4, remnoise);
+	_mav_put_uint16_t(buf, 5, rxerrors);
 	_mav_put_uint16_t(buf, 7, fixed);
 
 	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, 9);
@@ -160,8 +170,9 @@ static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi,
 	packet.rssi = rssi;
 	packet.remrssi = remrssi;
 	packet.txbuf = txbuf;
+	packet.noise = noise;
+	packet.remnoise = remnoise;
 	packet.rxerrors = rxerrors;
-	packet.serrors = serrors;
 	packet.fixed = fixed;
 
 	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, 9);
@@ -204,21 +215,31 @@ static inline uint8_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg)
 }
 
 /**
- * @brief Get field rxerrors from radio message
+ * @brief Get field noise from radio message
  *
- * @return receive errors
+ * @return background noise level
  */
-static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_radio_get_noise(const mavlink_message_t* msg)
+{
+	return _MAV_RETURN_uint8_t(msg,  3);
+}
+
+/**
+ * @brief Get field remnoise from radio message
+ *
+ * @return remote background noise level
+ */
+static inline uint8_t mavlink_msg_radio_get_remnoise(const mavlink_message_t* msg)
 {
-	return _MAV_RETURN_uint16_t(msg,  3);
+	return _MAV_RETURN_uint8_t(msg,  4);
 }
 
 /**
- * @brief Get field serrors from radio message
+ * @brief Get field rxerrors from radio message
  *
- * @return serial errors
+ * @return receive errors
  */
-static inline uint16_t mavlink_msg_radio_get_serrors(const mavlink_message_t* msg)
+static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* msg)
 {
 	return _MAV_RETURN_uint16_t(msg,  5);
 }
@@ -245,8 +266,9 @@ static inline void mavlink_msg_radio_decode(const mavlink_message_t* msg, mavlin
 	radio->rssi = mavlink_msg_radio_get_rssi(msg);
 	radio->remrssi = mavlink_msg_radio_get_remrssi(msg);
 	radio->txbuf = mavlink_msg_radio_get_txbuf(msg);
+	radio->noise = mavlink_msg_radio_get_noise(msg);
+	radio->remnoise = mavlink_msg_radio_get_remnoise(msg);
 	radio->rxerrors = mavlink_msg_radio_get_rxerrors(msg);
-	radio->serrors = mavlink_msg_radio_get_serrors(msg);
 	radio->fixed = mavlink_msg_radio_get_fixed(msg);
 #else
 	memcpy(radio, _MAV_PAYLOAD(msg), 9);
diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h b/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h
index d35e81bd4bd63270f95618465f1f746f808afe7c..cbc002d64f401b93ac90560e226fd86e5debe1ed 100644
--- a/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h
+++ b/libraries/GCS_MAVLink/include/ardupilotmega/testsuite.h
@@ -836,7 +836,8 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
 		5,
 	72,
 	139,
-	17391,
+	206,
+	17,
 	17495,
 	17599,
 	};
@@ -845,8 +846,9 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
 		packet1.rssi = packet_in.rssi;
 		packet1.remrssi = packet_in.remrssi;
 		packet1.txbuf = packet_in.txbuf;
+		packet1.noise = packet_in.noise;
+		packet1.remnoise = packet_in.remnoise;
 		packet1.rxerrors = packet_in.rxerrors;
-		packet1.serrors = packet_in.serrors;
 		packet1.fixed = packet_in.fixed;
 
 
@@ -857,12 +859,12 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-	mavlink_msg_radio_pack(system_id, component_id, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
+	mavlink_msg_radio_pack(system_id, component_id, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed );
 	mavlink_msg_radio_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-	mavlink_msg_radio_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
+	mavlink_msg_radio_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed );
 	mavlink_msg_radio_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -875,7 +877,7 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-	mavlink_msg_radio_send(MAVLINK_COMM_1 , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
+	mavlink_msg_radio_send(MAVLINK_COMM_1 , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed );
 	mavlink_msg_radio_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 }
diff --git a/libraries/GCS_MAVLink/include/ardupilotmega/version.h b/libraries/GCS_MAVLink/include/ardupilotmega/version.h
index 78e9d02f517adc0888e10a76d90b3ff75d32931f..92c94399fe27f24a364b13920f3aa95441dad220 100644
--- a/libraries/GCS_MAVLink/include/ardupilotmega/version.h
+++ b/libraries/GCS_MAVLink/include/ardupilotmega/version.h
@@ -5,7 +5,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Mon Apr  2 09:57:26 2012"
+#define MAVLINK_BUILD_DATE "Sun Apr  8 11:01:51 2012"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
  
diff --git a/libraries/GCS_MAVLink/include/common/version.h b/libraries/GCS_MAVLink/include/common/version.h
index edc521ae72d92c60ddc775582d10e9b2a7ae9832..4eab9a8979482ebcdf2b564ce6935e3c83570ca5 100644
--- a/libraries/GCS_MAVLink/include/common/version.h
+++ b/libraries/GCS_MAVLink/include/common/version.h
@@ -5,7 +5,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Mon Apr  2 09:57:26 2012"
+#define MAVLINK_BUILD_DATE "Sun Apr  8 11:01:51 2012"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
  
diff --git a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/ardupilotmega.h b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/ardupilotmega.h
index 0d168ba758b5f57f4fe6ed59e64c5b1c7f70188a..4325b57e21bcc0af9183326df894c4698dfc4899 100644
--- a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/ardupilotmega.h
+++ b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/ardupilotmega.h
@@ -16,7 +16,7 @@ extern "C" {
 #endif
 
 #ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 0, 0, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 42, 21, 244, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 247}
+#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 0, 0, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 42, 21, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 247}
 #endif
 
 #ifndef MAVLINK_MESSAGE_INFO
diff --git a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_radio.h b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_radio.h
index 546daddd1d4cd105855ae550317503327e7fa07c..db64da5c31d81512e2040b86a3db4c8d43654df6 100644
--- a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_radio.h
+++ b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/mavlink_msg_radio.h
@@ -5,11 +5,12 @@
 typedef struct __mavlink_radio_t
 {
  uint16_t rxerrors; ///< receive errors
- uint16_t serrors; ///< serial errors
  uint16_t fixed; ///< count of error corrected packets
  uint8_t rssi; ///< local signal strength
  uint8_t remrssi; ///< remote signal strength
  uint8_t txbuf; ///< how full the tx buffer is as a percentage
+ uint8_t noise; ///< background noise level
+ uint8_t remnoise; ///< remote background noise level
 } mavlink_radio_t;
 
 #define MAVLINK_MSG_ID_RADIO_LEN 9
@@ -19,13 +20,14 @@ typedef struct __mavlink_radio_t
 
 #define MAVLINK_MESSAGE_INFO_RADIO { \
 	"RADIO", \
-	6, \
+	7, \
 	{  { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_t, rxerrors) }, \
-         { "serrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_t, serrors) }, \
-         { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_radio_t, fixed) }, \
-         { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_t, rssi) }, \
-         { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_t, remrssi) }, \
-         { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_t, txbuf) }, \
+         { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_t, fixed) }, \
+         { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_t, rssi) }, \
+         { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_t, remrssi) }, \
+         { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_t, txbuf) }, \
+         { "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_t, noise) }, \
+         { "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_t, remnoise) }, \
          } \
 }
 
@@ -39,38 +41,41 @@ typedef struct __mavlink_radio_t
  * @param rssi local signal strength
  * @param remrssi remote signal strength
  * @param txbuf how full the tx buffer is as a percentage
+ * @param noise background noise level
+ * @param remnoise remote background noise level
  * @param rxerrors receive errors
- * @param serrors serial errors
  * @param fixed count of error corrected packets
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-						       uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint16_t rxerrors, uint16_t serrors, uint16_t fixed)
+						       uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
 	char buf[9];
 	_mav_put_uint16_t(buf, 0, rxerrors);
-	_mav_put_uint16_t(buf, 2, serrors);
-	_mav_put_uint16_t(buf, 4, fixed);
-	_mav_put_uint8_t(buf, 6, rssi);
-	_mav_put_uint8_t(buf, 7, remrssi);
-	_mav_put_uint8_t(buf, 8, txbuf);
+	_mav_put_uint16_t(buf, 2, fixed);
+	_mav_put_uint8_t(buf, 4, rssi);
+	_mav_put_uint8_t(buf, 5, remrssi);
+	_mav_put_uint8_t(buf, 6, txbuf);
+	_mav_put_uint8_t(buf, 7, noise);
+	_mav_put_uint8_t(buf, 8, remnoise);
 
         memcpy(_MAV_PAYLOAD(msg), buf, 9);
 #else
 	mavlink_radio_t packet;
 	packet.rxerrors = rxerrors;
-	packet.serrors = serrors;
 	packet.fixed = fixed;
 	packet.rssi = rssi;
 	packet.remrssi = remrssi;
 	packet.txbuf = txbuf;
+	packet.noise = noise;
+	packet.remnoise = remnoise;
 
         memcpy(_MAV_PAYLOAD(msg), &packet, 9);
 #endif
 
 	msg->msgid = MAVLINK_MSG_ID_RADIO;
-	return mavlink_finalize_message(msg, system_id, component_id, 9, 244);
+	return mavlink_finalize_message(msg, system_id, component_id, 9, 21);
 }
 
 /**
@@ -82,39 +87,42 @@ static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t compone
  * @param rssi local signal strength
  * @param remrssi remote signal strength
  * @param txbuf how full the tx buffer is as a percentage
+ * @param noise background noise level
+ * @param remnoise remote background noise level
  * @param rxerrors receive errors
- * @param serrors serial errors
  * @param fixed count of error corrected packets
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
 							   mavlink_message_t* msg,
-						           uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint16_t rxerrors,uint16_t serrors,uint16_t fixed)
+						           uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
 	char buf[9];
 	_mav_put_uint16_t(buf, 0, rxerrors);
-	_mav_put_uint16_t(buf, 2, serrors);
-	_mav_put_uint16_t(buf, 4, fixed);
-	_mav_put_uint8_t(buf, 6, rssi);
-	_mav_put_uint8_t(buf, 7, remrssi);
-	_mav_put_uint8_t(buf, 8, txbuf);
+	_mav_put_uint16_t(buf, 2, fixed);
+	_mav_put_uint8_t(buf, 4, rssi);
+	_mav_put_uint8_t(buf, 5, remrssi);
+	_mav_put_uint8_t(buf, 6, txbuf);
+	_mav_put_uint8_t(buf, 7, noise);
+	_mav_put_uint8_t(buf, 8, remnoise);
 
         memcpy(_MAV_PAYLOAD(msg), buf, 9);
 #else
 	mavlink_radio_t packet;
 	packet.rxerrors = rxerrors;
-	packet.serrors = serrors;
 	packet.fixed = fixed;
 	packet.rssi = rssi;
 	packet.remrssi = remrssi;
 	packet.txbuf = txbuf;
+	packet.noise = noise;
+	packet.remnoise = remnoise;
 
         memcpy(_MAV_PAYLOAD(msg), &packet, 9);
 #endif
 
 	msg->msgid = MAVLINK_MSG_ID_RADIO;
-	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 244);
+	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 21);
 }
 
 /**
@@ -127,7 +135,7 @@ static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t co
  */
 static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_t* radio)
 {
-	return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->rxerrors, radio->serrors, radio->fixed);
+	return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed);
 }
 
 /**
@@ -137,34 +145,37 @@ static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t compo
  * @param rssi local signal strength
  * @param remrssi remote signal strength
  * @param txbuf how full the tx buffer is as a percentage
+ * @param noise background noise level
+ * @param remnoise remote background noise level
  * @param rxerrors receive errors
- * @param serrors serial errors
  * @param fixed count of error corrected packets
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint16_t rxerrors, uint16_t serrors, uint16_t fixed)
+static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
 	char buf[9];
 	_mav_put_uint16_t(buf, 0, rxerrors);
-	_mav_put_uint16_t(buf, 2, serrors);
-	_mav_put_uint16_t(buf, 4, fixed);
-	_mav_put_uint8_t(buf, 6, rssi);
-	_mav_put_uint8_t(buf, 7, remrssi);
-	_mav_put_uint8_t(buf, 8, txbuf);
+	_mav_put_uint16_t(buf, 2, fixed);
+	_mav_put_uint8_t(buf, 4, rssi);
+	_mav_put_uint8_t(buf, 5, remrssi);
+	_mav_put_uint8_t(buf, 6, txbuf);
+	_mav_put_uint8_t(buf, 7, noise);
+	_mav_put_uint8_t(buf, 8, remnoise);
 
-	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, 9, 244);
+	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, 9, 21);
 #else
 	mavlink_radio_t packet;
 	packet.rxerrors = rxerrors;
-	packet.serrors = serrors;
 	packet.fixed = fixed;
 	packet.rssi = rssi;
 	packet.remrssi = remrssi;
 	packet.txbuf = txbuf;
+	packet.noise = noise;
+	packet.remnoise = remnoise;
 
-	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, 9, 244);
+	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, 9, 21);
 #endif
 }
 
@@ -180,7 +191,7 @@ static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi,
  */
 static inline uint8_t mavlink_msg_radio_get_rssi(const mavlink_message_t* msg)
 {
-	return _MAV_RETURN_uint8_t(msg,  6);
+	return _MAV_RETURN_uint8_t(msg,  4);
 }
 
 /**
@@ -190,7 +201,7 @@ static inline uint8_t mavlink_msg_radio_get_rssi(const mavlink_message_t* msg)
  */
 static inline uint8_t mavlink_msg_radio_get_remrssi(const mavlink_message_t* msg)
 {
-	return _MAV_RETURN_uint8_t(msg,  7);
+	return _MAV_RETURN_uint8_t(msg,  5);
 }
 
 /**
@@ -200,27 +211,37 @@ static inline uint8_t mavlink_msg_radio_get_remrssi(const mavlink_message_t* msg
  */
 static inline uint8_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg)
 {
-	return _MAV_RETURN_uint8_t(msg,  8);
+	return _MAV_RETURN_uint8_t(msg,  6);
 }
 
 /**
- * @brief Get field rxerrors from radio message
+ * @brief Get field noise from radio message
  *
- * @return receive errors
+ * @return background noise level
  */
-static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_radio_get_noise(const mavlink_message_t* msg)
 {
-	return _MAV_RETURN_uint16_t(msg,  0);
+	return _MAV_RETURN_uint8_t(msg,  7);
 }
 
 /**
- * @brief Get field serrors from radio message
+ * @brief Get field remnoise from radio message
  *
- * @return serial errors
+ * @return remote background noise level
  */
-static inline uint16_t mavlink_msg_radio_get_serrors(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_radio_get_remnoise(const mavlink_message_t* msg)
 {
-	return _MAV_RETURN_uint16_t(msg,  2);
+	return _MAV_RETURN_uint8_t(msg,  8);
+}
+
+/**
+ * @brief Get field rxerrors from radio message
+ *
+ * @return receive errors
+ */
+static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* msg)
+{
+	return _MAV_RETURN_uint16_t(msg,  0);
 }
 
 /**
@@ -230,7 +251,7 @@ static inline uint16_t mavlink_msg_radio_get_serrors(const mavlink_message_t* ms
  */
 static inline uint16_t mavlink_msg_radio_get_fixed(const mavlink_message_t* msg)
 {
-	return _MAV_RETURN_uint16_t(msg,  4);
+	return _MAV_RETURN_uint16_t(msg,  2);
 }
 
 /**
@@ -243,11 +264,12 @@ static inline void mavlink_msg_radio_decode(const mavlink_message_t* msg, mavlin
 {
 #if MAVLINK_NEED_BYTE_SWAP
 	radio->rxerrors = mavlink_msg_radio_get_rxerrors(msg);
-	radio->serrors = mavlink_msg_radio_get_serrors(msg);
 	radio->fixed = mavlink_msg_radio_get_fixed(msg);
 	radio->rssi = mavlink_msg_radio_get_rssi(msg);
 	radio->remrssi = mavlink_msg_radio_get_remrssi(msg);
 	radio->txbuf = mavlink_msg_radio_get_txbuf(msg);
+	radio->noise = mavlink_msg_radio_get_noise(msg);
+	radio->remnoise = mavlink_msg_radio_get_remnoise(msg);
 #else
 	memcpy(radio, _MAV_PAYLOAD(msg), 9);
 #endif
diff --git a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h
index 12f9aad722b6b1d1e201a8e0e8582cf14b4adf16..acd50ec021101c092b8ef06cee078273463cd262 100644
--- a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h
+++ b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/testsuite.h
@@ -835,7 +835,8 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
 	mavlink_radio_t packet_in = {
 		17235,
 	17339,
-	17443,
+	17,
+	84,
 	151,
 	218,
 	29,
@@ -843,11 +844,12 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
 	mavlink_radio_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
 		packet1.rxerrors = packet_in.rxerrors;
-		packet1.serrors = packet_in.serrors;
 		packet1.fixed = packet_in.fixed;
 		packet1.rssi = packet_in.rssi;
 		packet1.remrssi = packet_in.remrssi;
 		packet1.txbuf = packet_in.txbuf;
+		packet1.noise = packet_in.noise;
+		packet1.remnoise = packet_in.remnoise;
 
 
 
@@ -857,12 +859,12 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-	mavlink_msg_radio_pack(system_id, component_id, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
+	mavlink_msg_radio_pack(system_id, component_id, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed );
 	mavlink_msg_radio_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-	mavlink_msg_radio_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
+	mavlink_msg_radio_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed );
 	mavlink_msg_radio_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -875,7 +877,7 @@ static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-	mavlink_msg_radio_send(MAVLINK_COMM_1 , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.rxerrors , packet1.serrors , packet1.fixed );
+	mavlink_msg_radio_send(MAVLINK_COMM_1 , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed );
 	mavlink_msg_radio_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 }
diff --git a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/version.h b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/version.h
index 979dcb63672740859fb65647b089f6537ace68ba..1544c0de52879c963ddd1671ba221d307403bb4c 100644
--- a/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/version.h
+++ b/libraries/GCS_MAVLink/include_v1.0/ardupilotmega/version.h
@@ -5,7 +5,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Mon Apr  2 09:57:26 2012"
+#define MAVLINK_BUILD_DATE "Sun Apr  8 11:01:52 2012"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
  
diff --git a/libraries/GCS_MAVLink/include_v1.0/common/version.h b/libraries/GCS_MAVLink/include_v1.0/common/version.h
index 4941c1f8853d9fa160f67bc6274ed03841af07e8..f683e8c872932200937552542d9726e584da159d 100644
--- a/libraries/GCS_MAVLink/include_v1.0/common/version.h
+++ b/libraries/GCS_MAVLink/include_v1.0/common/version.h
@@ -5,7 +5,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Mon Apr  2 09:57:26 2012"
+#define MAVLINK_BUILD_DATE "Sun Apr  8 11:01:52 2012"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
  
diff --git a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
index c2ed19bf251d6cf4b682d97e6e0f9b883a3dd07f..c6019e03f24a8dae74646f103d19675740b7424c 100644
--- a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
+++ b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
@@ -261,8 +261,9 @@
             <field type="uint8_t" name="rssi">local signal strength</field>
             <field type="uint8_t" name="remrssi">remote signal strength</field>
 	    <field type="uint8_t" name="txbuf">how full the tx buffer is as a percentage</field>
+            <field type="uint8_t" name="noise">background noise level</field>
+            <field type="uint8_t" name="remnoise">remote background noise level</field>
 	    <field type="uint16_t" name="rxerrors">receive errors</field>
-	    <field type="uint16_t" name="serrors">serial errors</field>
 	    <field type="uint16_t" name="fixed">count of error corrected packets</field>
 	  </message>
      </messages>
diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml
index c2ed19bf251d6cf4b682d97e6e0f9b883a3dd07f..c6019e03f24a8dae74646f103d19675740b7424c 100644
--- a/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml
+++ b/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml
@@ -261,8 +261,9 @@
             <field type="uint8_t" name="rssi">local signal strength</field>
             <field type="uint8_t" name="remrssi">remote signal strength</field>
 	    <field type="uint8_t" name="txbuf">how full the tx buffer is as a percentage</field>
+            <field type="uint8_t" name="noise">background noise level</field>
+            <field type="uint8_t" name="remnoise">remote background noise level</field>
 	    <field type="uint16_t" name="rxerrors">receive errors</field>
-	    <field type="uint16_t" name="serrors">serial errors</field>
 	    <field type="uint16_t" name="fixed">count of error corrected packets</field>
 	  </message>
      </messages>