diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h
index f0470aa974b101ab61e83210133af5b40d5fceae..b7e4218405af50630c83eeb1ff9be80404841e84 100644
--- a/ArduCopter/Parameters.h
+++ b/ArduCopter/Parameters.h
@@ -379,14 +379,14 @@ public:
     AP_Int16        heli_stab_col_min;                                          // min collective while pilot directly controls collective in stabilize mode
     AP_Int16        heli_stab_col_max;                                          // min collective while pilot directly controls collective in stabilize mode
 #endif
-#if FRAME_CONFIG ==     SINGLE_FRAME
-    // Single
-    RC_Channel      single_servo_1, single_servo_2, single_servo_3, single_servo_4;     // servos for four flaps
+#if FRAME_CONFIG ==     SINGLE_FRAME
+    // Single
+    RC_Channel      single_servo_1, single_servo_2, single_servo_3, single_servo_4;     // servos for four flaps
 #endif
 
-#if FRAME_CONFIG ==     COAX_FRAME
-    // Coax copter flaps
-    RC_Channel      single_servo_1, single_servo_2; // servos for two flaps
+#if FRAME_CONFIG ==     COAX_FRAME
+    // Coax copter flaps
+    RC_Channel      single_servo_1, single_servo_2; // servos for two flaps
 #endif
 
     // RC channels
@@ -446,16 +446,16 @@ public:
         heli_servo_3        (CH_3),
         heli_servo_4        (CH_4),
 #endif
-#if FRAME_CONFIG ==     SINGLE_FRAME
-        single_servo_1        (CH_1),
-        single_servo_2        (CH_2),
-        single_servo_3        (CH_3),
-        single_servo_4        (CH_4),
+#if FRAME_CONFIG ==     SINGLE_FRAME
+        single_servo_1        (CH_1),
+        single_servo_2        (CH_2),
+        single_servo_3        (CH_3),
+        single_servo_4        (CH_4),
 #endif
 
-#if FRAME_CONFIG ==     COAX_FRAME
-        single_servo_1        (CH_1),
-        single_servo_2        (CH_2),
+#if FRAME_CONFIG ==     COAX_FRAME
+        single_servo_1        (CH_1),
+        single_servo_2        (CH_2),
 #endif
 
         rc_1                (CH_1),