mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Plane: prevent GPS speed spikes at startup from breaking airspeed cal
the filter can be affected by a huge GPS velocity spike
This commit is contained in:
parent
fe56ac3839
commit
8dd0aa12ed
@ -969,7 +969,8 @@ static void airspeed_ratio_update(void)
|
||||
{
|
||||
if (!airspeed.enabled() ||
|
||||
g_gps->status() < GPS::GPS_OK_FIX_3D ||
|
||||
g_gps->ground_speed_cm < 400) {
|
||||
g_gps->ground_speed_cm < 400 ||
|
||||
airspeed.get_airspeed() < aparm.airspeed_min) {
|
||||
return;
|
||||
}
|
||||
airspeed.update_calibration(g_gps->velocity_vector());
|
||||
|
Loading…
Reference in New Issue
Block a user