From 5d06e4238f6393254266e4829c59e12ce49095c7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 27 Feb 2017 17:39:46 +1100 Subject: [PATCH] Plane: make the quadplane motors var_info dynamic this will allow for more quadplane motors class types --- ArduPlane/quadplane.cpp | 11 +++++------ ArduPlane/quadplane.h | 2 ++ 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index ca70c583e3..ad2c4f77ff 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -11,7 +11,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_SUBGROUPVARPTR(motors, "M_", 2, QuadPlane, plane.quadplane.motors_var_info), // 3 ~ 8 were used by quadplane attitude control PIDs @@ -482,20 +482,19 @@ bool QuadPlane::setup(void) break; } - const struct AP_Param::GroupInfo *var_info; switch (motor_class) { case AP_Motors::MOTOR_FRAME_TRI: motors = new AP_MotorsTri(plane.scheduler.get_loop_rate_hz()); - var_info = AP_MotorsTri::var_info; + motors_var_info = AP_MotorsTri::var_info; break; case AP_Motors::MOTOR_FRAME_TAILSITTER: motors = new AP_MotorsTailsitter(plane.scheduler.get_loop_rate_hz()); - var_info = AP_MotorsTailsitter::var_info; + motors_var_info = AP_MotorsTailsitter::var_info; rotation = ROTATION_PITCH_90; break; default: motors = new AP_MotorsMatrix(plane.scheduler.get_loop_rate_hz()); - var_info = AP_MotorsMatrix::var_info; + motors_var_info = AP_MotorsMatrix::var_info; break; } const static char *strUnableToAllocate = "Unable to allocate"; @@ -504,7 +503,7 @@ bool QuadPlane::setup(void) goto failed; } - AP_Param::load_object_from_eeprom(motors, var_info); + AP_Param::load_object_from_eeprom(motors, motors_var_info); // create the attitude view used by the VTOL code ahrs_view = ahrs.create_view(rotation); diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 641f45b657..2eabd894a1 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -122,6 +122,8 @@ private: AP_Int8 frame_type; AP_MotorsMulticopter *motors; + const struct AP_Param::GroupInfo *motors_var_info; + AC_AttitudeControl_Multi *attitude_control; AC_PosControl *pos_control; AC_WPNav *wp_nav;