mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Baro: slow down Baro offset slew
This commit is contained in:
parent
74c2855be3
commit
813c732a83
@ -899,7 +899,7 @@ void AP_Baro::update(void)
|
||||
if (fabsf(_alt_offset - _alt_offset_active) > 0.01f) {
|
||||
// If there's more than 1cm difference then slowly slew to it via LPF.
|
||||
// The EKF does not like step inputs so this keeps it happy.
|
||||
_alt_offset_active = (0.95f*_alt_offset_active) + (0.05f*_alt_offset);
|
||||
_alt_offset_active = (0.98f*_alt_offset_active) + (0.02f*_alt_offset);
|
||||
} else {
|
||||
_alt_offset_active = _alt_offset;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user