AP_Baro: check for all 1 ADC read on MS5611

This commit is contained in:
Andrew Tridgell 2019-07-31 10:30:50 +10:00
parent 834e43f339
commit 4e59b8d24a

View File

@ -291,9 +291,10 @@ void AP_Baro_MS56XX::_timer(void)
}
/* if we had a failed read we are all done */
if (adc_val == 0) {
if (adc_val == 0 || adc_val == 0xFFFFFF) {
// a failed read can mean the next returned value will be
// corrupt, we must discard it
// corrupt, we must discard it. This copes with MISO being
// pulled either high or low
_discard_next = true;
return;
}