diff --git a/ArduPlane/APM_Config.h b/ArduPlane/APM_Config.h
index 88ceaf7f88101ca44c75f4f547da57fdcbac850e..472e771236cab7b7875586010e78a259bcb40c23 100644
--- a/ArduPlane/APM_Config.h
+++ b/ArduPlane/APM_Config.h
@@ -37,4 +37,4 @@
 #define THROTTLE_FAILSAFE   ENABLED
 */
 
-# define CONFIG_APM_HARDWARE APM_HARDWARE_APM1
+//# define CONFIG_APM_HARDWARE APM_HARDWARE_APM1
diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde
index 08a95021396c0da828af4cd16daaa3e628be6097..e8b0e7021650c18108286011b44e981b1cdbf7c4 100644
--- a/ArduPlane/Attitude.pde
+++ b/ArduPlane/Attitude.pde
@@ -314,7 +314,6 @@ static void set_servos(void)
 		if (g.mix_mode == 0) {
 			g.channel_roll.calc_pwm();
 			g.channel_pitch.calc_pwm();
-			g.channel_rudder.calc_pwm();
 			if (g_rc_function[RC_Channel_aux::k_aileron]) {
 				g_rc_function[RC_Channel_aux::k_aileron]->servo_out = g.channel_roll.servo_out;
 				g_rc_function[RC_Channel_aux::k_aileron]->calc_pwm();
@@ -329,6 +328,7 @@ static void set_servos(void)
 			g.channel_roll.radio_out =	elevon1_trim + (BOOL_TO_SIGN(g.reverse_ch1_elevon) * (ch1 * 500.0/ SERVO_MAX));
 			g.channel_pitch.radio_out =	elevon2_trim + (BOOL_TO_SIGN(g.reverse_ch2_elevon) * (ch2 * 500.0/ SERVO_MAX));
 		}
+		g.channel_rudder.calc_pwm();
 
 		#if THROTTLE_OUT == 0
 			g.channel_throttle.servo_out = 0;
diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde
index e0a8b870b91b9803c7fdfdf2f4a7c67c567d58dd..0db507a1761acfeaea12afb684e53fbafb4a4961 100644
--- a/ArduPlane/radio.pde
+++ b/ArduPlane/radio.pde
@@ -158,7 +158,6 @@ static void trim_control_surfaces()
 	if(g.mix_mode == 0){
 		g.channel_roll.radio_trim = g.channel_roll.radio_in;
 		g.channel_pitch.radio_trim = g.channel_pitch.radio_in;
-		g.channel_rudder.radio_trim = g.channel_rudder.radio_in;
 		G_RC_AUX(k_aileron)->radio_trim = g_rc_function[RC_Channel_aux::k_aileron]->radio_in;			// Second aileron channel
 
 	}else{
@@ -170,6 +169,7 @@ static void trim_control_surfaces()
 		g.channel_roll.radio_trim 	= center;
 		g.channel_pitch.radio_trim 	= center;
 	}
+	g.channel_rudder.radio_trim = g.channel_rudder.radio_in;
 
 	// save to eeprom
 	g.channel_roll.save_eeprom();
@@ -191,7 +191,6 @@ static void trim_radio()
 		g.channel_roll.radio_trim 		= g.channel_roll.radio_in;
 		g.channel_pitch.radio_trim 		= g.channel_pitch.radio_in;
 		//g.channel_throttle.radio_trim 	= g.channel_throttle.radio_in;
-		g.channel_rudder.radio_trim 	= g.channel_rudder.radio_in;
 		G_RC_AUX(k_aileron)->radio_trim = g_rc_function[RC_Channel_aux::k_aileron]->radio_in;			// Second aileron channel
 
 	} else {
@@ -200,8 +199,8 @@ static void trim_radio()
 		uint16_t center = 1500;
 		g.channel_roll.radio_trim 	= center;
 		g.channel_pitch.radio_trim 	= center;
-		g.channel_rudder.radio_trim = g.channel_rudder.radio_in;
 	}
+	g.channel_rudder.radio_trim = g.channel_rudder.radio_in;
 
 	// save to eeprom
 	g.channel_roll.save_eeprom();
diff --git a/ArduPlane/test.pde b/ArduPlane/test.pde
index e4ebfdcfa118b128cb6ce0ac19105b34b259a76f..8f0259dfc86625c9263e5f3202498de110a493cc 100644
--- a/ArduPlane/test.pde
+++ b/ArduPlane/test.pde
@@ -432,6 +432,7 @@ test_dipswitches(uint8_t argc, const Menu::arg *argv)
 				(int)g.reverse_elevons,
 				(int)g.reverse_ch1_elevon,
 				(int)g.reverse_ch2_elevon);
+				//(int)g.channel_rudder.get_reverse()); No reversing switch for rudder in elevon mode.
 		}
 		if(Serial.available() > 0){
 			return (0);