From 9c0d984a4effba5817405cc2fb3b1e13c16d6eb9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 28 Apr 2016 22:37:24 +1000 Subject: [PATCH] Plane: support forced motor class in quadplane --- ArduPlane/quadplane.cpp | 10 +++++++++- ArduPlane/quadplane.h | 5 ++++- 2 files changed, 13 insertions(+), 2 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 3bb5f22885..2bd93bd68b 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -13,7 +13,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Group: M_ // @Path: ../libraries/AP_Motors/AP_MotorsMulticopter.cpp - AP_SUBGROUPPTR(motors, "M_", 2, QuadPlane, AP_MotorsMulticopter), + AP_SUBGROUPPTR(motors, "M_", 2, QuadPlane, AP_MOTORS_CLASS), // 3 ~ 8 were used by quadplane attitude control PIDs @@ -303,6 +303,13 @@ bool QuadPlane::setup(void) goto failed; } +#ifdef AP_MOTORS_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); + RC_Channel_aux::set_aux_channel_default(RC_Channel_aux::k_motor7, CH_11); + motors = new AP_MOTORS_CLASS(plane.scheduler.get_loop_rate_hz()); +#else /* dynamically allocate the key objects for quadplane. This ensures that the objects don't affect the vehicle unless enabled and @@ -333,6 +340,7 @@ bool QuadPlane::setup(void) hal.console->printf("Unknown frame class %u\n", (unsigned)frame_class.get()); goto failed; } +#endif // AP_MOTORS_CLASS if (!motors) { hal.console->printf("Unable to allocate motors\n"); goto failed; diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 4961fd2ef5..46fb0369d2 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -7,6 +7,9 @@ #include #include +// uncomment this to force a different motor class +// #define AP_MOTORS_CLASS AP_MotorsTri + /* QuadPlane specific functionality */ @@ -97,7 +100,7 @@ private: AP_Int8 frame_class; AP_Int8 frame_type; - AP_MotorsMulticopter *motors; + AP_MOTORS_CLASS *motors; AC_AttitudeControl_Multi *attitude_control; AC_PosControl *pos_control; AC_WPNav *wp_nav;