diff --git a/libraries/AP_Baro/AP_Baro_MS5611.cpp b/libraries/AP_Baro/AP_Baro_MS5611.cpp index 86a531deb5..a23a17ef6b 100644 --- a/libraries/AP_Baro/AP_Baro_MS5611.cpp +++ b/libraries/AP_Baro/AP_Baro_MS5611.cpp @@ -264,9 +264,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; }