mirror of https://github.com/ArduPilot/ardupilot
AR_AttitudeControl: reduce steer rate P default to 0.2
This commit is contained in:
parent
e8726865ab
commit
54d8a4852f
|
@ -8,7 +8,7 @@
|
|||
// attitude control default definition
|
||||
#define AR_ATTCONTROL_STEER_ANG_P 1.00f
|
||||
#define AR_ATTCONTROL_STEER_RATE_FF 0.20f
|
||||
#define AR_ATTCONTROL_STEER_RATE_P 1.00f
|
||||
#define AR_ATTCONTROL_STEER_RATE_P 0.20f
|
||||
#define AR_ATTCONTROL_STEER_RATE_I 0.50f
|
||||
#define AR_ATTCONTROL_STEER_RATE_IMAX 1.00f
|
||||
#define AR_ATTCONTROL_STEER_RATE_D 0.00f
|
||||
|
|
Loading…
Reference in New Issue