AP_Baro: slow down the LPF for slewing to a new GND_ALT_OFFSET

Instead of a couple seconds, make it about 15sec. This makes TECS happy by not glitching the height demand as much. When applied too fast the TECS height demand causes a large single oscillation as it chases the filter lag.
This commit is contained in:
Tom Pittenger 2016-05-05 15:20:53 -07:00
parent 37ee3b44d2
commit d55050e5e3
1 changed files with 4 additions and 4 deletions

View File

@ -346,10 +346,10 @@ void AP_Baro::init(void)
*/
void AP_Baro::update(void)
{
if (fabsf(_alt_offset - _alt_offset_active) > 0.1f) {
// if there's more than 10cm difference then slowly slew to it via LPF.
// The EKF does not like step inputs so this keeps it happy
_alt_offset_active = (0.9f*_alt_offset_active) + (0.1f*_alt_offset);
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);
} else {
_alt_offset_active = _alt_offset;
}