mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_InertialSensor_MPU6000: Fix FIFO reset
Change the sequence. Previous sequence was sometimes causing failure to initialize the IMU.
This commit is contained in:
parent
514b60cf5e
commit
a27d7f8a93
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user