mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Baro_MS5611: Fix state machine in case of error
If there is a read error, reading from the adc will return 0 but moreover, we need to re-initiate a read or else we are stuck forever. From MS5611-01BA03 datasheet, p. 10, CONVERSION SEQUENCE: "After the conversion, using ADC read command the result is clocked out with the MSB first. If the conversion is not executed before the ADC read command, or the ADC read command is repeated, it will give 0 as the output result."
This commit is contained in:
parent
17f9712254
commit
3b5d73b1fe
@ -286,6 +286,10 @@ void AP_Baro_MS56XX::_timer(void)
|
||||
if (_serial->write(CMD_CONVERT_D1_OSR4096)) { // Command to read pressure
|
||||
_state++;
|
||||
}
|
||||
} else {
|
||||
/* if read fails, re-initiate a temperature read command or we are
|
||||
* stuck */
|
||||
_serial->write(CMD_CONVERT_D2_OSR4096);
|
||||
}
|
||||
} else {
|
||||
uint32_t d1 = _serial->read_24bits(0);;
|
||||
@ -313,6 +317,10 @@ void AP_Baro_MS56XX::_timer(void)
|
||||
_state++;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
/* if read fails, re-initiate a pressure read command or we are
|
||||
* stuck */
|
||||
_serial->write(CMD_CONVERT_D1_OSR4096);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user