AC_AttControl: re-enable rate feedforward by default

Roll and Pitch rate controllers became sluggish without feed-forward
enabled.
This commit is contained in:
Randy Mackay 2014-07-11 15:28:47 +09:00
parent 7f9cd20377
commit 5f623ac859
1 changed files with 1 additions and 1 deletions

View File

@ -40,7 +40,7 @@
#define AC_ATTITUDE_RATE_RP_PID_DTERM_FILTER 20 // D-term filter rate cutoff frequency for Roll and Pitch rate controllers
#define AC_ATTITUDE_RATE_Y_PID_DTERM_FILTER 5 // D-term filter rate cutoff frequency for Yaw rate controller
#define AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT 0 // body-frame rate feedforward disabled by default
#define AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT 1 // body-frame rate feedforward enabled by default
class AC_AttitudeControl {
public: