mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
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:
parent
7daaadf776
commit
13dac4a93a
@ -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…
Reference in New Issue
Block a user