Merge pull request #992 from blckmn/mpu6500_driver_updates

Some minor updates to the SPI MPU6500 driver to disable i2c interface
This commit is contained in:
borisbstyle 2016-08-13 22:54:10 +02:00 committed by GitHub
commit 28225ff0eb
6 changed files with 37 additions and 21 deletions

View File

@ -73,19 +73,6 @@ void mpu6500GyroInit(uint8_t lpf)
{
mpuIntExtiInit();
#ifdef NAZE
// FIXME target specific code in driver code.
gpio_config_t gpio;
// MPU_INT output on rev5 hardware (PC13). rev4 was on PB13, conflicts with SPI devices
if (hse_value == 12000000) {
gpio.pin = Pin_13;
gpio.speed = Speed_2MHz;
gpio.mode = Mode_IN_FLOATING;
gpioInit(GPIOC, &gpio);
}
#endif
mpuConfiguration.write(MPU_RA_PWR_MGMT_1, MPU6500_BIT_RESET);
delay(100);
mpuConfiguration.write(MPU_RA_SIGNAL_PATH_RESET, 0x07);
@ -105,11 +92,14 @@ void mpu6500GyroInit(uint8_t lpf)
// Data ready interrupt configuration
#ifdef USE_MPU9250_MAG
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
mpuConfiguration.write(MPU_RA_INT_PIN_CFG, MPU6500_BIT_INT_ANYRD_2CLEAR | MPU6500_BIT_BYPASS_EN); // INT_ANYRD_2CLEAR, BYPASS_EN
#else
mpuConfiguration.write(MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 0 << 1 | 0 << 0); // INT_ANYRD_2CLEAR, BYPASS_EN
mpuConfiguration.write(MPU_RA_INT_PIN_CFG, MPU6500_BIT_INT_ANYRD_2CLEAR); // INT_ANYRD_2CLEAR
#endif
delay(15);
#ifdef USE_MPU_DATA_READY_SIGNAL
mpuConfiguration.write(MPU_RA_INT_ENABLE, 0x01); // RAW_RDY_EN interrupt enable
mpuConfiguration.write(MPU_RA_INT_ENABLE, MPU6500_BIT_RAW_RDY_EN); // RAW_RDY_EN interrupt enable
#endif
delay(15);
}

View File

@ -20,6 +20,10 @@
#define ICM20608G_WHO_AM_I_CONST (0xAF)
#define MPU6500_BIT_RESET (0x80)
#define MPU6500_BIT_INT_ANYRD_2CLEAR (1 << 4)
#define MPU6500_BIT_BYPASS_EN (1 << 0)
#define MPU6500_BIT_I2C_IF_DIS (1 << 4)
#define MPU6500_BIT_RAW_RDY_EN (0x01)
#pragma once

View File

@ -205,8 +205,8 @@ bool mpu6000SpiDetect(void)
return false;
}
static void mpu6000AccAndGyroInit(void) {
static void mpu6000AccAndGyroInit(void)
{
if (mpuSpi6000InitDone) {
return;
}

View File

@ -91,13 +91,33 @@ bool mpu6500SpiDetect(void)
return false;
}
void mpu6500SpiAccInit(acc_t *acc)
{
mpu6500AccInit(acc);
}
void mpu6500SpiGyroInit(uint8_t lpf)
{
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_CLOCK_SLOW);
delayMicroseconds(1);
mpu6500GyroInit(lpf);
// Disable Primary I2C Interface
mpu6500WriteRegister(MPU_RA_USER_CTRL, MPU6500_BIT_I2C_IF_DIS);
delay(100);
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_CLOCK_FAST);
delayMicroseconds(1);
}
bool mpu6500SpiAccDetect(acc_t *acc)
{
if (mpuDetectionResult.sensor != MPU_65xx_SPI) {
return false;
}
acc->init = mpu6500AccInit;
acc->init = mpu6500SpiAccInit;
acc->read = mpuAccRead;
return true;
@ -109,7 +129,7 @@ bool mpu6500SpiGyroDetect(gyro_t *gyro)
return false;
}
gyro->init = mpu6500GyroInit;
gyro->init = mpu6500SpiGyroInit;
gyro->read = mpuGyroRead;
gyro->intStatus = checkMPUDataReady;

View File

@ -19,6 +19,9 @@
bool mpu6500SpiDetect(void);
void mpu6500SpiAccInit(acc_t *acc);
void mpu6500SpiGyroInit(uint8_t lpf);
bool mpu6500SpiAccDetect(acc_t *acc);
bool mpu6500SpiGyroDetect(gyro_t *gyro);

View File

@ -43,7 +43,6 @@
// MPU6500 interrupt
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
//#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define MPU_INT_EXTI PC5
#define MPU6500_CS_PIN PC4