ArduCopter Channel Config: config vars for user override of MOT_n mapping

* config variable CONFIG_CHANNELS has possible values
  CHANNEL_CONFIG_DEFAULT or CHANNEL_CONFIG_CUSTOM
* config_channels.h only provides APM1/APM2 mapping when
  CONFIG_CHANNELS == CHANNEL_CONFIG_DEFAULT
This commit is contained in:
Pat Hickey 2012-02-11 15:53:09 -08:00
parent 0315221bd1
commit db4195b7a0
3 changed files with 34 additions and 19 deletions

View File

@ -188,6 +188,13 @@
# define CONFIG_SONAR ENABLED # define CONFIG_SONAR ENABLED
#endif #endif
//////////////////////////////////////////////////////////////////////////////
// Channel Config (custom MOT channel mappings)
//
#ifndef CONFIG_CHANNELS
# define CONFIG_CHANNELS CHANNEL_CONFIG_DEFAULT
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Acrobatics // Acrobatics

View File

@ -16,13 +16,15 @@
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// //
#include "config.h" #include "config.h" // Parent Config File
#include "APM_Config.h" // User Overrides
// //
// //
// Output CH mapping for ArduCopter motor channels // Output CH mapping for ArduCopter motor channels
// //
// //
#if CONFIG_CHANNELS == CHANNEL_CONFIG_DEFAULT
# if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 # if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
# define MOT_1 CH_1 # define MOT_1 CH_1
# define MOT_2 CH_2 # define MOT_2 CH_2
@ -42,6 +44,7 @@
# define MOT_7 CH_10 # define MOT_7 CH_10
# define MOT_8 CH_11 # define MOT_8 CH_11
# endif # endif
#endif
// //
// //

View File

@ -369,4 +369,9 @@ enum gcs_severity {
#define LOGGING_SIMPLE 1 #define LOGGING_SIMPLE 1
#define LOGGING_VERBOSE 2 #define LOGGING_VERBOSE 2
// Channel Config selection
#define CHANNEL_CONFIG_DEFAULT 1
#define CHANNEL_CONFIG_CUSTOM 2
#endif // _DEFINES_H #endif // _DEFINES_H