AR_AttitudeControl: reduce default steering I gain to 0.2
Also reduce default filter from 50hz to 10hz
This commit is contained in:
parent
e5c0b1814a
commit
23ed735304
@ -9,17 +9,17 @@
|
||||
#define AR_ATTCONTROL_STEER_ANG_P 1.00f
|
||||
#define AR_ATTCONTROL_STEER_RATE_FF 0.20f
|
||||
#define AR_ATTCONTROL_STEER_RATE_P 0.20f
|
||||
#define AR_ATTCONTROL_STEER_RATE_I 0.50f
|
||||
#define AR_ATTCONTROL_STEER_RATE_I 0.20f
|
||||
#define AR_ATTCONTROL_STEER_RATE_IMAX 1.00f
|
||||
#define AR_ATTCONTROL_STEER_RATE_D 0.00f
|
||||
#define AR_ATTCONTROL_STEER_RATE_FILT 50.00f
|
||||
#define AR_ATTCONTROL_STEER_RATE_FILT 10.00f
|
||||
#define AR_ATTCONTROL_STEER_RATE_MAX 360.0f
|
||||
#define AR_ATTCONTROL_STEER_ACCEL_MAX 360.0f
|
||||
#define AR_ATTCONTROL_THR_SPEED_P 0.20f
|
||||
#define AR_ATTCONTROL_THR_SPEED_I 0.20f
|
||||
#define AR_ATTCONTROL_THR_SPEED_IMAX 1.00f
|
||||
#define AR_ATTCONTROL_THR_SPEED_D 0.00f
|
||||
#define AR_ATTCONTROL_THR_SPEED_FILT 50.00f
|
||||
#define AR_ATTCONTROL_THR_SPEED_FILT 10.00f
|
||||
#define AR_ATTCONTROL_DT 0.02f
|
||||
#define AR_ATTCONTROL_TIMEOUT_MS 200
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user