MPU6500 / AK8963 driver interoperation fix

This commit is contained in:
Michael Jakob 2017-04-20 20:16:25 +02:00
parent bb5314b825
commit 434f4f661d
11 changed files with 11 additions and 18 deletions

View File

@ -74,11 +74,7 @@ void mpu6500GyroInit(gyroDev_t *gyro)
delay(100);
// Data ready interrupt configuration
#ifdef USE_MPU9250_MAG
gyro->mpuConfiguration.writeFn(&gyro->bus, MPU_RA_INT_PIN_CFG, MPU6500_BIT_INT_ANYRD_2CLEAR | MPU6500_BIT_BYPASS_EN); // INT_ANYRD_2CLEAR, BYPASS_EN
#else
gyro->mpuConfiguration.writeFn(&gyro->bus, MPU_RA_INT_PIN_CFG, MPU6500_BIT_INT_ANYRD_2CLEAR); // INT_ANYRD_2CLEAR
#endif
delay(15);
#ifdef USE_MPU_DATA_READY_SIGNAL

View File

@ -49,6 +49,14 @@ bool mpu6500SpiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data)
return true;
}
bool mpu6500SpiWriteRegisterDelayed(const busDevice_t *bus, uint8_t reg, uint8_t data)
{
mpu6500SpiWriteRegister(bus, reg, data);
delayMicroseconds(10);
return true;
}
bool mpu6500SpiReadRegister(const busDevice_t *bus, uint8_t reg, uint8_t length, uint8_t *data)
{
ENABLE_MPU6500(bus->spi.csnPin);

View File

@ -25,6 +25,7 @@ bool mpu6500SpiAccDetect(accDev_t *acc);
bool mpu6500SpiGyroDetect(gyroDev_t *gyro);
bool mpu6500SpiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data);
bool mpu6500SpiWriteRegisterDelayed(const busDevice_t *bus, uint8_t reg, uint8_t data);
bool mpu6500SpiReadRegister(const busDevice_t *bus, uint8_t reg, uint8_t length, uint8_t *data);
void mpu6500SpiGyroInit(gyroDev_t *gyro);

View File

@ -88,7 +88,7 @@ static busDevice_t *bus = NULL; // HACK
// Is an separate MPU9250 driver really needed? The GYRO/ACC part between MPU6500 and MPU9250 is exactly the same.
#if defined(MPU6500_SPI_INSTANCE) && !defined(MPU9250_SPI_INSTANCE)
#define MPU9250_SPI_INSTANCE
#define verifympu9250SpiWriteRegister mpu6500SpiWriteRegister
#define verifympu9250SpiWriteRegister mpu6500SpiWriteRegisterDelayed
#define mpu9250SpiWriteRegister mpu6500SpiWriteRegister
#define mpu9250SpiReadRegister mpu6500SpiReadRegister
#endif
@ -116,7 +116,7 @@ static bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t
verifympu9250SpiWriteRegister(bus, MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes
delay(10);
__disable_irq();
bool ack = mpu9250SpiReadRegister(bus, MPU_RA_EXT_SENS_DATA_00, len_, buf); // read I2C
bool ack = mpu9250SpiReadRegister(bus, MPU_RA_EXT_SENS_DATA_00, len_, buf); // read I2C
__enable_irq();
return ack;
}

View File

@ -34,7 +34,6 @@
#include "rx/rx.h"
#include "sensors/compass.h"
#include "sensors/gyro.h"
#include "hardware_revision.h"
@ -81,7 +80,6 @@ void targetConfiguration(void)
rxConfigMutable()->spektrum_sat_bind = 5;
rxConfigMutable()->spektrum_sat_bind_autoreset = 1;
compassConfigMutable()->mag_hardware = MAG_NONE; // disabled by default
if (hardwareMotorType == MOTOR_BRUSHED) {
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;

View File

@ -40,7 +40,6 @@
#include "telemetry/telemetry.h"
#include "sensors/battery.h"
#include "sensors/compass.h"
#include "hardware_revision.h"
@ -53,8 +52,6 @@
// alternative defaults settings for AlienFlight targets
void targetConfiguration(void)
{
compassConfigMutable()->mag_hardware = MAG_NONE; // disabled by default
if (hardwareMotorType == MOTOR_BRUSHED) {
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
pidConfigMutable()->pid_process_denom = 1;

View File

@ -39,7 +39,6 @@
#include "telemetry/telemetry.h"
#include "sensors/battery.h"
#include "sensors/compass.h"
#include "hardware_revision.h"
@ -52,8 +51,6 @@
// alternative defaults settings for AlienFlight targets
void targetConfiguration(void)
{
compassConfigMutable()->mag_hardware = MAG_NONE; // disabled by default
if (hardwareMotorType == MOTOR_BRUSHED) {
motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
pidConfigMutable()->pid_process_denom = 1;

View File

@ -73,7 +73,6 @@
#define USE_BARO_MS5611
#define MAG
#define USE_MPU9250_MAG
#define USE_MAG_HMC5883
#define USE_MAG_AK8963
#define USE_MAG_AK8975

View File

@ -48,7 +48,6 @@
#define USE_BARO_MS5611
#define MAG
#define USE_MPU9250_MAG // Enables bypass configuration
#define USE_MAG_AK8975
#define USE_MAG_HMC5883 // External

View File

@ -58,7 +58,6 @@
#define USE_BARO_BMP280
#define MAG
#define USE_MPU9250_MAG // Enables bypass configuration
#define USE_MAG_AK8963
//#define USE_MAG_HMC5883 // External

View File

@ -66,7 +66,6 @@
#define USE_BARO_BMP280
#define MAG
#define USE_MPU9250_MAG // Enables bypass configuration
#define USE_MAG_AK8975
#define USE_MAG_HMC5883 // External
#define MAG_AK8975_ALIGN CW90_DEG_FLIP