1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 08:15:30 +03:00

Merge pull request #2910 from AlienWiiBF/MPU6500_fix

MPU6500 / AK8963 driver interoperation fix
This commit is contained in:
MJ666 2017-04-23 09:50:41 +02:00 committed by GitHub
commit a871a7f3e0
13 changed files with 16 additions and 15 deletions

View file

@ -49,6 +49,14 @@ bool mpu6500SpiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data)
return true; 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) bool mpu6500SpiReadRegister(const busDevice_t *bus, uint8_t reg, uint8_t length, uint8_t *data)
{ {
ENABLE_MPU6500(bus->spi.csnPin); ENABLE_MPU6500(bus->spi.csnPin);

View file

@ -25,6 +25,7 @@ bool mpu6500SpiAccDetect(accDev_t *acc);
bool mpu6500SpiGyroDetect(gyroDev_t *gyro); bool mpu6500SpiGyroDetect(gyroDev_t *gyro);
bool mpu6500SpiWriteRegister(const busDevice_t *bus, uint8_t reg, uint8_t data); 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); bool mpu6500SpiReadRegister(const busDevice_t *bus, uint8_t reg, uint8_t length, uint8_t *data);
void mpu6500SpiGyroInit(gyroDev_t *gyro); 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. // 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) #if defined(MPU6500_SPI_INSTANCE) && !defined(MPU9250_SPI_INSTANCE)
#define MPU9250_SPI_INSTANCE #define MPU9250_SPI_INSTANCE
#define verifympu9250SpiWriteRegister mpu6500SpiWriteRegister #define verifympu9250SpiWriteRegister mpu6500SpiWriteRegisterDelayed
#define mpu9250SpiWriteRegister mpu6500SpiWriteRegister #define mpu9250SpiWriteRegister mpu6500SpiWriteRegister
#define mpu9250SpiReadRegister mpu6500SpiReadRegister #define mpu9250SpiReadRegister mpu6500SpiReadRegister
#endif #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 verifympu9250SpiWriteRegister(bus, MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes
delay(10); delay(10);
__disable_irq(); __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(); __enable_irq();
return ack; return ack;
} }

View file

@ -2700,8 +2700,8 @@ static void cliTasks(char *cmdline)
if (systemConfig()->task_statistics) { if (systemConfig()->task_statistics) {
cfCheckFuncInfo_t checkFuncInfo; cfCheckFuncInfo_t checkFuncInfo;
getCheckFuncInfo(&checkFuncInfo); getCheckFuncInfo(&checkFuncInfo);
cliPrintLinef("RX Check Function %17d %7d %25d", checkFuncInfo.maxExecutionTime, checkFuncInfo.averageExecutionTime, checkFuncInfo.totalExecutionTime / 1000); cliPrintLinef("RX Check Function %19d %7d %25d", checkFuncInfo.maxExecutionTime, checkFuncInfo.averageExecutionTime, checkFuncInfo.totalExecutionTime / 1000);
cliPrintLinef("Total (excluding SERIAL) %23d.%1d%% %4d.%1d%%", maxLoadSum/10, maxLoadSum%10, averageLoadSum/10, averageLoadSum%10); cliPrintLinef("Total (excluding SERIAL) %25d.%1d%% %4d.%1d%%", maxLoadSum/10, maxLoadSum%10, averageLoadSum/10, averageLoadSum%10);
} }
} }
#endif #endif

View file

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

View file

@ -90,6 +90,7 @@
#define UART3_RX_PIN PB11 #define UART3_RX_PIN PB11
#define USE_I2C #define USE_I2C
#define USE_I2C_PULLUP
#define USE_I2C_DEVICE_2 #define USE_I2C_DEVICE_2
#define I2C_DEVICE (I2CDEV_2) #define I2C_DEVICE (I2CDEV_2)
#define I2C2_SCL PA9 #define I2C2_SCL PA9

View file

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

View file

@ -138,6 +138,7 @@
#define USE_SPI_DEVICE_3 #define USE_SPI_DEVICE_3
#define USE_I2C #define USE_I2C
#define USE_I2C_PULLUP
#define USE_I2C_DEVICE_1 #define USE_I2C_DEVICE_1
#define I2C_DEVICE (I2CDEV_1) #define I2C_DEVICE (I2CDEV_1)
#define I2C1_SCL PB6 #define I2C1_SCL PB6

View file

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

View file

@ -149,6 +149,7 @@
#define SPI3_MOSI_PIN PB5 #define SPI3_MOSI_PIN PB5
#define USE_I2C #define USE_I2C
#define USE_I2C_PULLUP
#define I2C_DEVICE (I2CDEV_1) #define I2C_DEVICE (I2CDEV_1)
//#define I2C_DEVICE_EXT (I2CDEV_2) //#define I2C_DEVICE_EXT (I2CDEV_2)
#define I2C1_SCL PB6 #define I2C1_SCL PB6

View file

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

View file

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

View file

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