From f4976394de4da3ebe2eb47a41cfcd8a1fed2bd0a Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 26 Apr 2018 14:16:22 +0900 Subject: [PATCH] AR_AttitudeControl: increase angle err P and reduce steering accel max defaults --- libraries/APM_Control/AR_AttitudeControl.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/APM_Control/AR_AttitudeControl.h b/libraries/APM_Control/AR_AttitudeControl.h index 57e78fdd72..216ba8a64a 100644 --- a/libraries/APM_Control/AR_AttitudeControl.h +++ b/libraries/APM_Control/AR_AttitudeControl.h @@ -6,7 +6,7 @@ #include // attitude control default definition -#define AR_ATTCONTROL_STEER_ANG_P 1.00f +#define AR_ATTCONTROL_STEER_ANG_P 2.50f #define AR_ATTCONTROL_STEER_RATE_FF 0.20f #define AR_ATTCONTROL_STEER_RATE_P 0.20f #define AR_ATTCONTROL_STEER_RATE_I 0.20f @@ -14,7 +14,7 @@ #define AR_ATTCONTROL_STEER_RATE_D 0.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_STEER_ACCEL_MAX 180.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