mirror of https://github.com/ArduPilot/ardupilot
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:
parent
77eea3a893
commit
6e1798b104
|
@ -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));
|
||||
|
|
Loading…
Reference in New Issue