Browse Source

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
mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
13dac4a93a
  1. 2
      libraries/AP_DCM/AP_DCM.h

2
libraries/AP_DCM/AP_DCM.h

@ -26,7 +26,7 @@ public: @@ -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,

Loading…
Cancel
Save