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