AP_InertialSensor: prevented MPU9250 from disabling I2C slaves

This commit is contained in:
Staroselskii Georgii 2014-11-24 15:33:27 +03:00 committed by Andrew Tridgell
parent a08a34f863
commit f7f9cd2173

View File

@ -418,7 +418,11 @@ bool AP_InertialSensor_MPU9250::_hardware_init(void)
// Chip reset
uint8_t tries;
for (tries = 0; tries<5; tries++) {
#if CONFIG_COMPASS != HAL_COMPASS_AK8963
/* Prevent reseting if internal AK8963 is selected, because it may corrupt
* AK8963's initialisation. */
_register_write(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_DEVICE_RESET);
#endif
hal.scheduler->delay(100);
// Wake up device and select GyroZ clock. Note that the
@ -444,7 +448,11 @@ bool AP_InertialSensor_MPU9250::_hardware_init(void)
_register_write(MPUREG_PWR_MGMT_2, 0x00); // only used for wake-up in accelerometer only low power mode
// Disable I2C bus (recommended on datasheet)
#if CONFIG_COMPASS != HAL_COMPASS_AK8963
/* Prevent disabling if internal AK8963 is selected. If internal AK8963 is not used
* it's ok to disable I2C slaves*/
_register_write(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);
#endif
_default_filter_hz = _default_filter();