mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_Compass: workaround hardware bug in IST8310 whoami
the WAI (whoami) register is writeable. Not only is it writeable, but the written value is persistent across a power cycle. You have to remove power for about 30s for it to finally go back to the right default value of 0x10 this makes using WAI as a test for finding a IST8310 problematic. The best we can do is send a soft reset which will reset it to default for us to then check
This commit is contained in:
parent
30d3c5c9d6
commit
e92c38454b
@ -113,6 +113,22 @@ bool AP_Compass_IST8310::init()
|
|||||||
// high retries for init
|
// high retries for init
|
||||||
_dev->set_retries(10);
|
_dev->set_retries(10);
|
||||||
|
|
||||||
|
/*
|
||||||
|
unfortunately the IST8310 employs the novel concept of a
|
||||||
|
writeable WHOAMI register. The register can become corrupt due
|
||||||
|
to bus noise, and what is worse it persists the corruption even
|
||||||
|
across a power cycle. If you power it off for 30s or more then
|
||||||
|
it will reset to the default of 0x10, but for less than that the
|
||||||
|
value of WAI is unreliable.
|
||||||
|
|
||||||
|
To avoid this issue we do a reset of the device before we probe
|
||||||
|
the WAI register. This is nasty as we don't yet know we've found
|
||||||
|
a real IST8310, but it is the best we can do given the bad
|
||||||
|
hardware design of the sensor
|
||||||
|
*/
|
||||||
|
_dev->write_register(CNTL2_REG, CNTL2_VAL_SRST);
|
||||||
|
hal.scheduler->delay(10);
|
||||||
|
|
||||||
uint8_t whoami;
|
uint8_t whoami;
|
||||||
if (!_dev->read_registers(WAI_REG, &whoami, 1) ||
|
if (!_dev->read_registers(WAI_REG, &whoami, 1) ||
|
||||||
whoami != DEVICE_ID) {
|
whoami != DEVICE_ID) {
|
||||||
|
Loading…
Reference in New Issue
Block a user