From 3b2d203f0fb2f420388406f05954e59e8eae6583 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Mon, 30 Apr 2012 14:34:15 +0900 Subject: [PATCH] AP_AHRS: updated default AHRS_YAW_P to 0.2 (was 0.4) This reduces the compass's default authority over the yaw direction by half --- libraries/AP_AHRS/AP_AHRS_DCM.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index 97c163d1dc..d4bb46f474 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -17,7 +17,7 @@ public: AP_AHRS_DCM(IMU *imu, GPS *&gps) : AP_AHRS(imu, gps) { _kp_roll_pitch = 0.13; - _kp_yaw.set(0.4); + _kp_yaw.set(0.2); _dcm_matrix(Vector3f(1, 0, 0), Vector3f(0, 1, 0), Vector3f(0, 0, 1));