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
This commit is contained in:
rmackay9 2012-04-30 14:34:15 +09:00
parent 77eea3a893
commit 6e1798b104
1 changed files with 1 additions and 1 deletions

View File

@ -17,7 +17,7 @@ public:
AP_AHRS_DCM(IMU *imu, GPS *&gps) : AP_AHRS(imu, gps) AP_AHRS_DCM(IMU *imu, GPS *&gps) : AP_AHRS(imu, gps)
{ {
_kp_roll_pitch = 0.13; _kp_roll_pitch = 0.13;
_kp_yaw.set(0.4); _kp_yaw.set(0.2);
_dcm_matrix(Vector3f(1, 0, 0), _dcm_matrix(Vector3f(1, 0, 0),
Vector3f(0, 1, 0), Vector3f(0, 1, 0),
Vector3f(0, 0, 1)); Vector3f(0, 0, 1));