Fix warm reboot jitter issue for SPI targets

This commit is contained in:
borisbstyle 2016-01-12 17:10:30 +01:00
parent d74be40f1f
commit 77d9d1d2b9
2 changed files with 13 additions and 8 deletions

View File

@ -97,10 +97,15 @@ void mpu6500GyroInit(uint8_t lpf)
mpuConfiguration.write(MPU_RA_PWR_MGMT_1, 0);
delay(100);
mpuConfiguration.write(MPU_RA_PWR_MGMT_1, INV_CLK_PLL);
delay(15);
mpuConfiguration.write(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3);
delay(15);
mpuConfiguration.write(MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3);
delay(15);
mpuConfiguration.write(MPU_RA_CONFIG, lpf);
delay(15);
mpuConfiguration.write(MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops()); // Get Divider Drops
delay(100);
// Data ready interrupt configuration
mpuConfiguration.write(MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_ANYRD_2CLEAR, BYPASS_EN

View File

@ -215,35 +215,35 @@ static void mpu6000AccAndGyroInit(void) {
// Clock Source PPL with Z axis gyro reference
mpu6000WriteRegister(MPU_RA_PWR_MGMT_1, MPU_CLK_SEL_PLLGYROZ);
delayMicroseconds(1);
delayMicroseconds(15);
// Disable Primary I2C Interface
mpu6000WriteRegister(MPU_RA_USER_CTRL, BIT_I2C_IF_DIS);
delayMicroseconds(1);
delayMicroseconds(15);
mpu6000WriteRegister(MPU_RA_PWR_MGMT_2, 0x00);
delayMicroseconds(1);
delayMicroseconds(15);
// Accel Sample Rate 1kHz
// Gyroscope Output Rate = 1kHz when the DLPF is enabled
mpu6000WriteRegister(MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops());
delayMicroseconds(1);
delayMicroseconds(15);
// Gyro +/- 1000 DPS Full Scale
mpu6000WriteRegister(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3);
delayMicroseconds(1);
delayMicroseconds(15);
// Accel +/- 8 G Full Scale
mpu6000WriteRegister(MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3);
delayMicroseconds(1);
delayMicroseconds(15);
mpu6000WriteRegister(MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 0 << 1 | 0 << 0); // INT_ANYRD_2CLEAR
delayMicroseconds(1);
delayMicroseconds(15);
#ifdef USE_MPU_DATA_READY_SIGNAL
mpu6000WriteRegister(MPU_RA_INT_ENABLE, MPU_RF_DATA_RDY_EN);
delayMicroseconds(1);
delayMicroseconds(15);
#endif
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER); // 18 MHz SPI clock