From 5ee87f756114cba076fdbf6cbda04cc64fc978a5 Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Fri, 2 May 2014 17:44:09 -0400 Subject: [PATCH] Copter: Change TradHeli to use new AC_HELI_PID class. --- ArduCopter/ArduCopter.pde | 1 + ArduCopter/Parameters.h | 6 ++++++ ArduCopter/Parameters.pde | 13 +++++++++++++ 3 files changed, 20 insertions(+) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 22ee4c0a76..8eea022543 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -115,6 +115,7 @@ #include // Mission command library #include // Rally point library #include // PID library +#include // Heli specific Rate PID library #include // P library #include // Attitude control library #include // Attitude control library for traditional helicopter diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 4b0274794e..771f3d50fc 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -430,9 +430,15 @@ public: AP_Int8 acro_trainer; // PI/D controllers +#if FRAME_CONFIG == HELI_FRAME + AC_HELI_PID pid_rate_roll; + AC_HELI_PID pid_rate_pitch; + AC_HELI_PID pid_rate_yaw; +#else AC_PID pid_rate_roll; AC_PID pid_rate_pitch; AC_PID pid_rate_yaw; +#endif AC_PID pid_loiter_rate_lat; AC_PID pid_loiter_rate_lon; diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 3a06e1ad46..ea1d675717 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -577,6 +577,7 @@ const AP_Param::Info var_info[] PROGMEM = { // PID controller //--------------- + // @Param: RATE_RLL_P // @DisplayName: Roll axis rate controller P gain // @Description: Roll axis rate controller P gain. Converts the difference between desired roll rate and actual roll rate into a motor speed output @@ -605,7 +606,11 @@ const AP_Param::Info var_info[] PROGMEM = { // @Range: 0.001 0.02 // @Increment: 0.001 // @User: Standard +#if FRAME_CONFIG == HELI_FRAME + GGROUP(pid_rate_roll, "RATE_RLL_", AC_HELI_PID), +#else GGROUP(pid_rate_roll, "RATE_RLL_", AC_PID), +#endif // @Param: RATE_PIT_P // @DisplayName: Pitch axis rate controller P gain @@ -635,7 +640,11 @@ const AP_Param::Info var_info[] PROGMEM = { // @Range: 0.001 0.02 // @Increment: 0.001 // @User: Standard +#if FRAME_CONFIG == HELI_FRAME + GGROUP(pid_rate_pitch, "RATE_PIT_", AC_HELI_PID), +#else GGROUP(pid_rate_pitch, "RATE_PIT_", AC_PID), +#endif // @Param: RATE_YAW_P // @DisplayName: Yaw axis rate controller P gain @@ -665,7 +674,11 @@ const AP_Param::Info var_info[] PROGMEM = { // @Range: 0.000 0.02 // @Increment: 0.001 // @User: Standard +#if FRAME_CONFIG == HELI_FRAME + GGROUP(pid_rate_yaw, "RATE_YAW_", AC_HELI_PID), +#else GGROUP(pid_rate_yaw, "RATE_YAW_", AC_PID), +#endif // @Param: LOITER_LAT_P // @DisplayName: Loiter latitude rate controller P gain