Skip to content

Commit

Permalink
AR_AttitudeControl: reduce default steering I gain to 0.2
Browse files Browse the repository at this point in the history
Also reduce default filter from 50hz to 10hz
  • Loading branch information
rmackay9 committed Apr 19, 2018
1 parent e5c0b18 commit 23ed735
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions libraries/APM_Control/AR_AttitudeControl.h
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down

0 comments on commit 23ed735

Please sign in to comment.