AP_Baro: work around bad WHOAMI read on DPS310

this fixes an issue with bad read of WHOAMI on a mRoPixracerPro. We
don't know how the sensor gets in a state where WHOAMI can't be read,
but toggling CS does fix it
This commit is contained in:
Andrew Tridgell 2021-03-31 11:33:49 +11:00
parent ded488fd9f
commit 46f35a6910
1 changed files with 6 additions and 0 deletions

View File

@ -164,6 +164,12 @@ bool AP_Baro_DPS280::init()
dev->set_speed(AP_HAL::Device::SPEED_HIGH);
// the DPS310 can get into a state on boot where the whoami is not
// read correctly at startup. Toggling the CS line gets its out of
// this state
dev->set_chip_select(true);
dev->set_chip_select(false);
uint8_t whoami=0;
if (!dev->read_registers(DPS280_REG_PID, &whoami, 1) ||
whoami != DPS280_WHOAMI) {