mirror of https://github.com/ArduPilot/ardupilot
Baro: update climb rate only if healthy
This commit is contained in:
parent
cc27fb46bf
commit
5732a6a144
|
@ -347,8 +347,10 @@ void AP_Baro::update(void)
|
|||
}
|
||||
|
||||
// ensure the climb rate filter is updated
|
||||
if (healthy()) {
|
||||
_climb_rate_filter.update(get_altitude(), get_last_update());
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
call accululate on all drivers
|
||||
|
|
Loading…
Reference in New Issue