diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h index b61e4cc4de..a802883951 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h @@ -10,22 +10,22 @@ // default rate controller PID gains #define AC_ATC_HELI_RATE_RP_P 0.024f -#define AC_ATC_HELI_RATE_RP_I 0.6f +#define AC_ATC_HELI_RATE_RP_I 0.15f #define AC_ATC_HELI_RATE_RP_D 0.001f -#define AC_ATC_HELI_RATE_RP_IMAX 1.0f -#define AC_ATC_HELI_RATE_RP_FF 0.060f +#define AC_ATC_HELI_RATE_RP_IMAX 0.4f +#define AC_ATC_HELI_RATE_RP_FF 0.15f #define AC_ATC_HELI_RATE_RP_FILT_HZ 20.0f #define AC_ATC_HELI_RATE_YAW_P 0.18f #define AC_ATC_HELI_RATE_YAW_I 0.12f #define AC_ATC_HELI_RATE_YAW_D 0.003f -#define AC_ATC_HELI_RATE_YAW_IMAX 1.0f +#define AC_ATC_HELI_RATE_YAW_IMAX 0.4f #define AC_ATC_HELI_RATE_YAW_FF 0.024f #define AC_ATC_HELI_RATE_YAW_FILT_HZ 20.0f #define AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX 0.95f // Heli's use 95% of max collective before limiting frame angle #define AC_ATTITUDE_HELI_RATE_INTEGRATOR_LEAK_RATE 0.02f -#define AC_ATTITUDE_HELI_RATE_RP_FF_FILTER 10.0f -#define AC_ATTITUDE_HELI_RATE_Y_FF_FILTER 10.0f +#define AC_ATTITUDE_HELI_RATE_RP_FF_FILTER 20.0f +#define AC_ATTITUDE_HELI_RATE_Y_FF_FILTER 20.0f #define AC_ATTITUDE_HELI_HOVER_ROLL_TRIM_DEFAULT 300 #define AC_ATTITUDE_HELI_ACRO_OVERSHOOT_ANGLE_RAD ToRad(30.0f)