mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Compass: added retries on init in BMM150
This commit is contained in:
parent
9b093c4a33
commit
68460144df
@ -133,6 +133,9 @@ bool AP_Compass_BMM150::init()
|
||||
return false;
|
||||
}
|
||||
|
||||
// 10 retries for init
|
||||
_dev->set_retries(10);
|
||||
|
||||
/* Do a soft reset */
|
||||
ret = _dev->write_register(POWER_AND_OPERATIONS_REG, SOFT_RESET);
|
||||
if (!ret) {
|
||||
@ -194,6 +197,9 @@ bool AP_Compass_BMM150::init()
|
||||
|
||||
_perf_err = hal.util->perf_alloc(AP_HAL::Util::PC_COUNT, "BMM150_err");
|
||||
|
||||
// 2 retries for run
|
||||
_dev->set_retries(2);
|
||||
|
||||
_dev->register_periodic_callback(MEASURE_TIME_USEC,
|
||||
FUNCTOR_BIND_MEMBER(&AP_Compass_BMM150::_update, void));
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user