From 13dac4a93a6ba7d7e70cc284a8cbe7c3d858baa8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 12 Mar 2012 17:49:15 +1100 Subject: [PATCH] DCM: adjust yaw kp constant down to 0.4 this makes the time constant for compass errors closely match the timing of the older releases - about 10 seconds for a 1 radian change in heading --- libraries/AP_DCM/AP_DCM.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_DCM/AP_DCM.h b/libraries/AP_DCM/AP_DCM.h index 5ebe7f554f..7c7b2a4217 100644 --- a/libraries/AP_DCM/AP_DCM.h +++ b/libraries/AP_DCM/AP_DCM.h @@ -26,7 +26,7 @@ public: // Constructors AP_DCM(IMU *imu, GPS *&gps) : _kp_roll_pitch(0.13), - _kp_yaw(0.8), + _kp_yaw(0.4), _gps(gps), _imu(imu), _dcm_matrix(1, 0, 0,