Copter: Change TradHeli to use new AC_HELI_PID class.

This commit is contained in:
Robert Lefebvre 2014-05-02 17:44:09 -04:00 committed by Randy Mackay
parent 6333b4bba6
commit 5ee87f7561
3 changed files with 20 additions and 0 deletions

View File

@ -115,6 +115,7 @@
#include <AP_Mission.h> // Mission command library
#include <AP_Rally.h> // Rally point library
#include <AC_PID.h> // PID library
#include <AC_HELI_PID.h> // Heli specific Rate PID library
#include <AC_P.h> // P library
#include <AC_AttitudeControl.h> // Attitude control library
#include <AC_AttitudeControl_Heli.h> // Attitude control library for traditional helicopter

View File

@ -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;

View File

@ -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