mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: stop blending if too many blending failures
This commit is contained in:
parent
b7ad8da9b9
commit
e9c881c668
|
@ -638,6 +638,10 @@ AP_GPS::update(void)
|
|||
} else if (_blend_health_counter > 0) {
|
||||
_blend_health_counter--;
|
||||
}
|
||||
// stop blending if unhealthy
|
||||
if (_blend_health_counter >= 50) {
|
||||
_output_is_blended = false;
|
||||
}
|
||||
} else {
|
||||
_output_is_blended = false;
|
||||
_blend_health_counter = 0;
|
||||
|
|
Loading…
Reference in New Issue