diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 185209475d..18798c36c0 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -188,6 +188,13 @@ # define CONFIG_SONAR ENABLED #endif +////////////////////////////////////////////////////////////////////////////// +// Channel Config (custom MOT channel mappings) +// + +#ifndef CONFIG_CHANNELS +# define CONFIG_CHANNELS CHANNEL_CONFIG_DEFAULT +#endif ////////////////////////////////////////////////////////////////////////////// // Acrobatics diff --git a/ArduCopter/config_channels.h b/ArduCopter/config_channels.h index b3a1e7263d..7fe44b0677 100644 --- a/ArduCopter/config_channels.h +++ b/ArduCopter/config_channels.h @@ -16,31 +16,34 @@ ////////////////////////////////////////////////////////////////////////////// // -#include "config.h" +#include "config.h" // Parent Config File +#include "APM_Config.h" // User Overrides // // // Output CH mapping for ArduCopter motor channels // // -#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 +#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 // diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index d4601ec17f..6b1f93a1df 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -369,4 +369,9 @@ enum gcs_severity { #define LOGGING_SIMPLE 1 #define LOGGING_VERBOSE 2 +// Channel Config selection + +#define CHANNEL_CONFIG_DEFAULT 1 +#define CHANNEL_CONFIG_CUSTOM 2 + #endif // _DEFINES_H