2011-12-30 13:41:35 -04:00
|
|
|
|
|
|
|
#ifndef __ARDUCOPTER_CONFIG_MOTORS_H__
|
|
|
|
#define __ARDUCOPTER_CONFIG_MOTORS_H__
|
|
|
|
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//
|
|
|
|
// WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING
|
|
|
|
//
|
|
|
|
// DO NOT EDIT this file to adjust your configuration. Create your own
|
|
|
|
// APM_Config.h and use APM_Config.h.example as a reference.
|
|
|
|
//
|
|
|
|
// WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING WARNING
|
2012-02-01 14:10:51 -04:00
|
|
|
///
|
2011-12-30 13:41:35 -04:00
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//////////////////////////////////////////////////////////////////////////////
|
|
|
|
//
|
|
|
|
|
|
|
|
#include "config.h"
|
|
|
|
|
|
|
|
//
|
|
|
|
//
|
|
|
|
// 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
|
2012-01-01 16:03:38 -04:00
|
|
|
# define MOT_5 CH_7
|
|
|
|
# define MOT_6 CH_8
|
|
|
|
# define MOT_7 CH_10
|
|
|
|
# define MOT_8 CH_11
|
2012-02-01 14:10:51 -04:00
|
|
|
#endif
|
2012-01-01 16:04:06 -04:00
|
|
|
|
2012-01-01 16:24:07 -04:00
|
|
|
//
|
|
|
|
//
|
|
|
|
// Output CH mapping for TRI_FRAME yaw servo
|
|
|
|
//
|
|
|
|
//
|
|
|
|
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
2012-01-27 11:39:01 -04:00
|
|
|
# define CH_TRI_YAW CH_7
|
2012-01-01 16:24:07 -04:00
|
|
|
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
|
|
|
|
# define CH_TRI_YAW CH_7
|
|
|
|
#endif
|
|
|
|
|
2012-01-01 16:04:06 -04:00
|
|
|
//
|
|
|
|
//
|
|
|
|
// Output CH mapping for Aux channels
|
|
|
|
//
|
|
|
|
//
|
|
|
|
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
2012-02-01 14:10:51 -04:00
|
|
|
/* Camera Pitch and Camera Roll: Not yet defined for APM2
|
2012-01-01 16:04:06 -04:00
|
|
|
* They will likely be dependent on the frame config */
|
2012-02-01 14:10:51 -04:00
|
|
|
# define CH_CAM_PITCH CH_11
|
|
|
|
# define CH_CAM_ROLL CH_10
|
2012-01-01 16:04:06 -04:00
|
|
|
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
|
|
|
|
# define CH_CAM_PITCH CH_5
|
|
|
|
# define CH_CAM_ROLL CH_6
|
2011-12-30 13:41:35 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#endif // __ARDUCOPTER_CONFIG_MOTORS_H__
|