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
This commit is contained in:
Andrew Tridgell 2012-03-12 17:49:15 +11:00
parent aa408655f8
commit 9a6adb9990
1 changed files with 1 additions and 1 deletions

View File

@ -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,