AC_AttControl: disable feed forward by default

Can be re-enabled by setting ATC_RATE_FF_ENAB parameter to 1
This commit is contained in:
Randy Mackay 2014-06-06 19:49:17 +09:00
parent b57c0dabf6
commit 02b4b21f67

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 1 // body-frame rate feedforward enabled by default
#define AC_ATTITUDE_CONTROL_RATE_BF_FF_DEFAULT 0 // body-frame rate feedforward disabled by default
class AC_AttitudeControl {
public: