AP_Baro: MS56XX: do not change change state on error

If we have an error in the SPI or I2C transaction we should not change
the state. Otherwise we might read a temperature when the sensor is
reporting pressure and vice-versa.
This commit is contained in:
Gustavo Jose de Sousa 2015-08-17 13:44:46 -03:00 committed by Andrew Tridgell
parent 1f29e18375
commit bcd5dff774

View File

@ -282,9 +282,11 @@ void AP_Baro_MS56XX::_timer(void)
_s_D2 >>= 1;
_d2_count = 16;
}
if (_serial->write(CMD_CONVERT_D1_OSR4096)) { // Command to read pressure
_state++;
}
}
_state++;
_serial->write(CMD_CONVERT_D1_OSR4096); // Command to read pressure
} else {
uint32_t d1 = _serial->read_24bits(0);;
if (d1 != 0) {
@ -301,13 +303,16 @@ void AP_Baro_MS56XX::_timer(void)
}
// Now a new reading exists
_updated = true;
}
_state++;
if (_state == 5) {
_serial->write(CMD_CONVERT_D2_OSR4096); // Command to read temperature
_state = 0;
} else {
_serial->write(CMD_CONVERT_D1_OSR4096); // Command to read pressure
if (_state == 4) {
if (_serial->write(CMD_CONVERT_D2_OSR4096)) { // Command to read temperature
_state = 0;
}
} else {
if (_serial->write(CMD_CONVERT_D1_OSR4096)) { // Command to read pressure
_state++;
}
}
}
}