mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Compass: added retries during init for i2c devices
higher in init, lower for run
This commit is contained in:
parent
28a318145c
commit
4f1f6ec019
@ -159,6 +159,9 @@ bool AP_Compass_HMC5843::init()
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// high retries for init
|
||||||
|
_bus->set_retries(10);
|
||||||
|
|
||||||
if (!_bus->configure()) {
|
if (!_bus->configure()) {
|
||||||
hal.console->printf("HMC5843: Could not configure the bus\n");
|
hal.console->printf("HMC5843: Could not configure the bus\n");
|
||||||
goto errout;
|
goto errout;
|
||||||
@ -185,6 +188,9 @@ bool AP_Compass_HMC5843::init()
|
|||||||
|
|
||||||
_initialised = true;
|
_initialised = true;
|
||||||
|
|
||||||
|
// lower retries for run
|
||||||
|
_bus->set_retries(3);
|
||||||
|
|
||||||
bus_sem->give();
|
bus_sem->give();
|
||||||
|
|
||||||
// perform an initial read
|
// perform an initial read
|
||||||
|
@ -89,6 +89,8 @@ public:
|
|||||||
|
|
||||||
// return 24 bit bus identifier
|
// return 24 bit bus identifier
|
||||||
virtual uint32_t get_bus_id(void) const = 0;
|
virtual uint32_t get_bus_id(void) const = 0;
|
||||||
|
|
||||||
|
virtual void set_retries(uint8_t retries) {}
|
||||||
};
|
};
|
||||||
|
|
||||||
class AP_HMC5843_BusDriver_HALDevice : public AP_HMC5843_BusDriver
|
class AP_HMC5843_BusDriver_HALDevice : public AP_HMC5843_BusDriver
|
||||||
@ -113,6 +115,10 @@ public:
|
|||||||
uint32_t get_bus_id(void) const override {
|
uint32_t get_bus_id(void) const override {
|
||||||
return _dev->get_bus_id();
|
return _dev->get_bus_id();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void set_retries(uint8_t retries) override {
|
||||||
|
return _dev->set_retries(retries);
|
||||||
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
|
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
|
||||||
|
@ -86,6 +86,9 @@ bool AP_Compass_LIS3MDL::init()
|
|||||||
dev->set_read_flag(0xC0);
|
dev->set_read_flag(0xC0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// high retries for init
|
||||||
|
dev->set_retries(10);
|
||||||
|
|
||||||
uint8_t whoami;
|
uint8_t whoami;
|
||||||
if (!dev->read_registers(ADDR_WHO_AM_I, &whoami, 1) ||
|
if (!dev->read_registers(ADDR_WHO_AM_I, &whoami, 1) ||
|
||||||
whoami != ID_WHO_AM_I) {
|
whoami != ID_WHO_AM_I) {
|
||||||
@ -100,6 +103,9 @@ bool AP_Compass_LIS3MDL::init()
|
|||||||
dev->write_register(ADDR_CTRL_REG3, 0, true); // continuous
|
dev->write_register(ADDR_CTRL_REG3, 0, true); // continuous
|
||||||
dev->write_register(ADDR_CTRL_REG4, 0x0C, true); // z-axis ultra high perf
|
dev->write_register(ADDR_CTRL_REG4, 0x0C, true); // z-axis ultra high perf
|
||||||
dev->write_register(ADDR_CTRL_REG5, 0x40, true); // block-data-update
|
dev->write_register(ADDR_CTRL_REG5, 0x40, true); // block-data-update
|
||||||
|
|
||||||
|
// lower retries for run
|
||||||
|
dev->set_retries(3);
|
||||||
|
|
||||||
dev->get_semaphore()->give();
|
dev->get_semaphore()->give();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user