mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Compass: Retry reading MMC5983 ID up to 10 times
This commit is contained in:
parent
b51d9e665e
commit
18c214907a
@ -78,9 +78,17 @@ bool AP_Compass_MMC5XX3::init()
|
|||||||
dev->set_read_flag(0x80);
|
dev->set_read_flag(0x80);
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t whoami;
|
// Reading REG_PRODUCT_ID fails sometimes on SPI, so we retry up to 10 times
|
||||||
if (!dev->read_registers(REG_PRODUCT_ID, &whoami, 1) ||
|
uint8_t whoami = 0;
|
||||||
whoami != MMC5983_ID) {
|
uint8_t tries = 10;
|
||||||
|
while (whoami == 0 && tries > 0) {
|
||||||
|
tries--;
|
||||||
|
dev->read_registers(REG_PRODUCT_ID, &whoami, 1);
|
||||||
|
hal.scheduler->delay(5);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (whoami != MMC5983_ID) {
|
||||||
|
printf("MMC5983 got unexpected product id: %d, expected: %d\n", whoami, MMC5983_ID);
|
||||||
// not a MMC5983
|
// not a MMC5983
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user