mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: disable I2C on MPU9250
As the datasheet says: "To prevent switching into I2C mode when using
SPI, the I2C interface should be disabled by setting the I2C_IF_DIS
configuration bit."
We also reset the sensor like PX4Firmware does for initializing the
MPU6000. See: ee1d8cd770/src/drivers/mpu6000/mpu6000.cpp (L695)
This commit is contained in:
parent
54c06cde02
commit
587471ab54
|
@ -421,8 +421,14 @@ bool AP_InertialSensor_MPU9250::_hardware_init(void)
|
||||||
// Chip reset
|
// Chip reset
|
||||||
uint8_t tries;
|
uint8_t tries;
|
||||||
for (tries = 0; tries<5; tries++) {
|
for (tries = 0; tries<5; tries++) {
|
||||||
|
// reset device
|
||||||
|
_register_write(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_DEVICE_RESET);
|
||||||
|
|
||||||
hal.scheduler->delay(100);
|
hal.scheduler->delay(100);
|
||||||
|
|
||||||
|
// disable I2C as recommended by the datasheet
|
||||||
|
_register_write(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);
|
||||||
|
|
||||||
// Wake up device and select GyroZ clock. Note that the
|
// Wake up device and select GyroZ clock. Note that the
|
||||||
// MPU6000 starts up in sleep mode, and it can take some time
|
// MPU6000 starts up in sleep mode, and it can take some time
|
||||||
// for it to come out of sleep
|
// for it to come out of sleep
|
||||||
|
|
Loading…
Reference in New Issue