From dd6c4d622559b7062766d034b65c35b7f183836d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 1 Apr 2016 16:17:07 +1100 Subject: [PATCH] Plane: fixed up parameters for quadplane this fixes quadplane parameters for the new AP_Motors code --- ArduPlane/Parameters.cpp | 6 ++++++ ArduPlane/Parameters.h | 1 + ArduPlane/quadplane.cpp | 4 ---- 3 files changed, 7 insertions(+), 4 deletions(-) diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 7db8eb144b..3e28a6c1ad 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1105,6 +1105,12 @@ const AP_Param::Info Plane::var_info[] = { // @Group: Q_ // @Path: quadplane.cpp GOBJECT(quadplane, "Q_", QuadPlane), + + // @Group: Q_A_ + // @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp + { AP_PARAM_GROUP, "Q_A_", Parameters::k_param_q_attitude_control, + (const void *)&plane.quadplane.attitude_control, + {group_info : AC_AttitudeControl_Multi::var_info}, AP_PARAM_FLAG_POINTER }, // RC channel //----------- diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index fafbb03241..3285aa7ee4 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -152,6 +152,7 @@ public: k_param_fence_retalt = 105, k_param_fence_autoenable, k_param_fence_ret_rally, + k_param_q_attitude_control, // 110: Telemetry control // diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 356bdda82b..6c5345a506 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -17,10 +17,6 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // 3 ~ 8 were used by quadplane attitude control PIDs - // @Group: ATC_ - // @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp - AP_SUBGROUPPTR(attitude_control, "A_", 9, QuadPlane, AC_AttitudeControl_Multi), - // @Param: ANGLE_MAX // @DisplayName: Angle Max // @Description: Maximum lean angle in all flight modes