AP_InertialSensor_MPU6000: Fix FIFO reset

Change the sequence. Previous sequence was sometimes causing failure
to initialize the IMU.
This commit is contained in:
Julien BERAUD 2015-12-14 17:53:09 +01:00 committed by Andrew Tridgell
parent 514b60cf5e
commit a27d7f8a93

View File

@ -328,7 +328,8 @@ void AP_MPU6000_BusDriver_I2C::start(bool &fifo_mode, uint8_t &max_samples)
fifo_mode = true;
write8(MPUREG_FIFO_EN, BIT_XG_FIFO_EN | BIT_YG_FIFO_EN |
BIT_ZG_FIFO_EN | BIT_ACCEL_FIFO_EN | BIT_TEMP_FIFO_EN);
write8(MPUREG_USER_CTRL, BIT_USER_CTRL_FIFO_RESET | BIT_USER_CTRL_SIG_COND_RESET);
write8(MPUREG_USER_CTRL, 0);
write8(MPUREG_USER_CTRL, BIT_USER_CTRL_FIFO_RESET);
write8(MPUREG_USER_CTRL, BIT_USER_CTRL_FIFO_EN);
/* maximum number of samples read by a burst
* a sample is an array containing :
@ -385,7 +386,7 @@ void AP_MPU6000_BusDriver_I2C::read_data_transaction(uint8_t *samples,
/* Too many samples, do a FIFO RESET */
write8(MPUREG_USER_CTRL, 0);
write8(MPUREG_USER_CTRL, BIT_USER_CTRL_FIFO_RESET | BIT_USER_CTRL_SIG_COND_RESET);
write8(MPUREG_USER_CTRL, BIT_USER_CTRL_FIFO_RESET);
write8(MPUREG_USER_CTRL, BIT_USER_CTRL_FIFO_EN);
n_samples = 0;
return;