mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_InertialSensor: disable reset on MPU9250
The Compass library is initialized before the InertialSensor. AK8963 with MPU9250 as backend already takes care of resetting MPU9250. The problem with also resetting it in the MPU9250 initialization code is that if the reset happens during an internal I2C transaction, the AK8963 may hang. So here we remove the reset inside MPU9250. There still a possibility that the first MPU9250 initialization is not successful and it resets the chip, but it's not happening in tests.
This commit is contained in:
parent
b93101b1bf
commit
d40b45c9ae
@ -417,11 +417,6 @@ bool AP_InertialSensor_MPU9250::_hardware_init(void)
|
||||
// Chip reset
|
||||
uint8_t 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);
|
||||
|
||||
// disable I2C as recommended by the datasheet
|
||||
_register_write(MPUREG_USER_CTRL, BIT_USER_CTRL_I2C_IF_DIS);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user