From 54d8a4852ff9a73f9cccfb1ce94c93ae20e36a33 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 9 Mar 2018 13:17:38 +0900 Subject: [PATCH] AR_AttitudeControl: reduce steer rate P default to 0.2 --- libraries/APM_Control/AR_AttitudeControl.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/APM_Control/AR_AttitudeControl.h b/libraries/APM_Control/AR_AttitudeControl.h index f17457ae79..1c862569ea 100644 --- a/libraries/APM_Control/AR_AttitudeControl.h +++ b/libraries/APM_Control/AR_AttitudeControl.h @@ -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