mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
DCM: after some experimentation, raise the ki values a bit
this tracks the max gyro drift more accurately
This commit is contained in:
parent
89b4a9f4ed
commit
fed5426274
@ -41,8 +41,8 @@ public:
|
||||
// which will make us less prone to increasing omegaI
|
||||
// incorrectly due to sensor noise
|
||||
_gyro_drift_limit = imu->get_gyro_drift_rate();
|
||||
_ki_roll_pitch = _gyro_drift_limit * 3;
|
||||
_ki_yaw = _gyro_drift_limit * 4;
|
||||
_ki_roll_pitch = _gyro_drift_limit * 5;
|
||||
_ki_yaw = _gyro_drift_limit * 8;
|
||||
}
|
||||
|
||||
// Accessors
|
||||
|
Loading…
Reference in New Issue
Block a user