From 23ed73530438d3ad055c63a3e02c7826119ab9d7 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 19 Apr 2018 16:29:12 +0900 Subject: [PATCH] AR_AttitudeControl: reduce default steering I gain to 0.2 Also reduce default filter from 50hz to 10hz --- libraries/APM_Control/AR_AttitudeControl.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/APM_Control/AR_AttitudeControl.h b/libraries/APM_Control/AR_AttitudeControl.h index c856c8aef1..57e78fdd72 100644 --- a/libraries/APM_Control/AR_AttitudeControl.h +++ b/libraries/APM_Control/AR_AttitudeControl.h @@ -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