Browse Source

Plane: support building quadplane with forced motors class

master
Andrew Tridgell 9 years ago
parent
commit
6f4d66f346
  1. 2
      ArduPlane/quadplane.cpp
  2. 9
      ArduPlane/quadplane.h

2
ArduPlane/quadplane.cpp

@ -303,7 +303,7 @@ bool QuadPlane::setup(void) @@ -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);

9
ArduPlane/quadplane.h

@ -8,7 +8,14 @@ @@ -8,7 +8,14 @@
#include <AC_WPNav/AC_WPNav.h>
// 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

Loading…
Cancel
Save