Plane: reset ground_start_count if we lose 3D fix
thanks to Michael for this suggestion
This commit is contained in:
parent
a427768087
commit
f514e76f52
@ -491,6 +491,9 @@ void Plane::update_GPS_10Hz(void)
|
||||
|
||||
// update wind estimate
|
||||
ahrs.estimate_wind();
|
||||
} else if (gps.status() < AP_GPS::GPS_OK_FIX_3D && ground_start_count != 0) {
|
||||
// lost 3D fix, start again
|
||||
ground_start_count = 5;
|
||||
}
|
||||
|
||||
calc_gndspeed_undershoot();
|
||||
|
Loading…
Reference in New Issue
Block a user