diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 2bd93bd68b..ead3dcdaf5 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -303,7 +303,7 @@ bool QuadPlane::setup(void) goto failed; } -#ifdef AP_MOTORS_CLASS +#ifdef AP_MOTORS_FORCE_CLASS RC_Channel_aux::set_aux_channel_default(RC_Channel_aux::k_motor1, CH_5); RC_Channel_aux::set_aux_channel_default(RC_Channel_aux::k_motor2, CH_6); RC_Channel_aux::set_aux_channel_default(RC_Channel_aux::k_motor4, CH_8); diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 46fb0369d2..f7788d5598 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -8,7 +8,14 @@ #include // uncomment this to force a different motor class -// #define AP_MOTORS_CLASS AP_MotorsTri +// #define AP_MOTORS_FORCE_CLASS AP_MotorsTri + + +#ifdef AP_MOTORS_FORCE_CLASS +#define AP_MOTORS_CLASS AP_MOTORS_FORCE_CLASS +#else +#define AP_MOTORS_CLASS AP_MotorsMulticopter +#endif /* QuadPlane specific functionality