mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 00:35:34 +03:00
Remove a duplicate MPU9250 driver; Fixed a bug when board hangs when acc_hardware is set to a non-existent sensor
This commit is contained in:
parent
8909cd8374
commit
11b31b0762
15 changed files with 37 additions and 372 deletions
|
@ -41,7 +41,6 @@
|
||||||
#include "accgyro_mpu6500.h"
|
#include "accgyro_mpu6500.h"
|
||||||
#include "accgyro_spi_mpu6000.h"
|
#include "accgyro_spi_mpu6000.h"
|
||||||
#include "accgyro_spi_mpu6500.h"
|
#include "accgyro_spi_mpu6500.h"
|
||||||
#include "accgyro_spi_mpu9250.h"
|
|
||||||
#include "accgyro_mpu.h"
|
#include "accgyro_mpu.h"
|
||||||
|
|
||||||
//#define DEBUG_MPU_DATA_READY_INTERRUPT
|
//#define DEBUG_MPU_DATA_READY_INTERRUPT
|
||||||
|
@ -152,19 +151,6 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_GYRO_SPI_MPU9250
|
|
||||||
if (mpu9250SpiDetect()) {
|
|
||||||
gyro->mpuDetectionResult.sensor = MPU_9250_SPI;
|
|
||||||
gyro->mpuConfiguration.gyroReadXRegister = MPU_RA_GYRO_XOUT_H;
|
|
||||||
gyro->mpuConfiguration.read = mpu9250ReadRegister;
|
|
||||||
gyro->mpuConfiguration.slowread = mpu9250SlowReadRegister;
|
|
||||||
gyro->mpuConfiguration.verifywrite = verifympu9250WriteRegister;
|
|
||||||
gyro->mpuConfiguration.write = mpu9250WriteRegister;
|
|
||||||
gyro->mpuConfiguration.reset = mpu9250ResetGyro;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
UNUSED(gyro);
|
UNUSED(gyro);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
|
@ -76,7 +76,7 @@ void mpu6500GyroInit(gyroDev_t *gyro)
|
||||||
delay(100);
|
delay(100);
|
||||||
gyro->mpuConfiguration.write(MPU_RA_PWR_MGMT_1, INV_CLK_PLL);
|
gyro->mpuConfiguration.write(MPU_RA_PWR_MGMT_1, INV_CLK_PLL);
|
||||||
delay(15);
|
delay(15);
|
||||||
gyro->mpuConfiguration.write(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3);
|
gyro->mpuConfiguration.write(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3 | FCB_DISABLED); //Fchoice_b defaults to 00 which makes fchoice 11
|
||||||
delay(15);
|
delay(15);
|
||||||
gyro->mpuConfiguration.write(MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3);
|
gyro->mpuConfiguration.write(MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3);
|
||||||
delay(15);
|
delay(15);
|
||||||
|
|
|
@ -1,238 +0,0 @@
|
||||||
/*
|
|
||||||
* This file is part of Cleanflight.
|
|
||||||
*
|
|
||||||
* Cleanflight is free software: you can redistribute it and/or modify
|
|
||||||
* it under the terms of the GNU General Public License as published by
|
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
|
||||||
* (at your option) any later version.
|
|
||||||
*
|
|
||||||
* Cleanflight is distributed in the hope that it will be useful,
|
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
||||||
* GNU General Public License for more details.
|
|
||||||
*
|
|
||||||
* You should have received a copy of the GNU General Public License
|
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*/
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Authors:
|
|
||||||
* Dominic Clifton - Cleanflight implementation
|
|
||||||
* John Ihlein - Initial FF32 code
|
|
||||||
* Kalyn Doerr (RS2K) - Robust rewrite
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <stdbool.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
|
|
||||||
#include "platform.h"
|
|
||||||
|
|
||||||
#include "build/debug.h"
|
|
||||||
|
|
||||||
#include "common/axis.h"
|
|
||||||
#include "common/maths.h"
|
|
||||||
|
|
||||||
#include "io.h"
|
|
||||||
|
|
||||||
#include "system.h"
|
|
||||||
#include "exti.h"
|
|
||||||
#include "bus_spi.h"
|
|
||||||
#include "gyro_sync.h"
|
|
||||||
#include "light_led.h"
|
|
||||||
|
|
||||||
#include "sensor.h"
|
|
||||||
#include "accgyro.h"
|
|
||||||
#include "accgyro_mpu.h"
|
|
||||||
#include "accgyro_spi_mpu9250.h"
|
|
||||||
|
|
||||||
static void mpu9250AccAndGyroInit(uint8_t lpf);
|
|
||||||
|
|
||||||
static bool mpuSpi9250InitDone = false;
|
|
||||||
|
|
||||||
static IO_t mpuSpi9250CsPin = IO_NONE;
|
|
||||||
|
|
||||||
#define DISABLE_MPU9250 IOHi(mpuSpi9250CsPin)
|
|
||||||
#define ENABLE_MPU9250 IOLo(mpuSpi9250CsPin)
|
|
||||||
|
|
||||||
void mpu9250ResetGyro(void)
|
|
||||||
{
|
|
||||||
// Device Reset
|
|
||||||
mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
|
|
||||||
delay(150);
|
|
||||||
}
|
|
||||||
|
|
||||||
bool mpu9250WriteRegister(uint8_t reg, uint8_t data)
|
|
||||||
{
|
|
||||||
ENABLE_MPU9250;
|
|
||||||
delayMicroseconds(1);
|
|
||||||
spiTransferByte(MPU9250_SPI_INSTANCE, reg);
|
|
||||||
spiTransferByte(MPU9250_SPI_INSTANCE, data);
|
|
||||||
DISABLE_MPU9250;
|
|
||||||
delayMicroseconds(1);
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool mpu9250ReadRegister(uint8_t reg, uint8_t length, uint8_t *data)
|
|
||||||
{
|
|
||||||
ENABLE_MPU9250;
|
|
||||||
spiTransferByte(MPU9250_SPI_INSTANCE, reg | 0x80); // read transaction
|
|
||||||
spiTransfer(MPU9250_SPI_INSTANCE, data, NULL, length);
|
|
||||||
DISABLE_MPU9250;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool mpu9250SlowReadRegister(uint8_t reg, uint8_t length, uint8_t *data)
|
|
||||||
{
|
|
||||||
ENABLE_MPU9250;
|
|
||||||
delayMicroseconds(1);
|
|
||||||
spiTransferByte(MPU9250_SPI_INSTANCE, reg | 0x80); // read transaction
|
|
||||||
spiTransfer(MPU9250_SPI_INSTANCE, data, NULL, length);
|
|
||||||
DISABLE_MPU9250;
|
|
||||||
delayMicroseconds(1);
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void mpu9250SpiGyroInit(gyroDev_t *gyro)
|
|
||||||
{
|
|
||||||
mpuGyroInit(gyro);
|
|
||||||
|
|
||||||
mpu9250AccAndGyroInit(gyro->lpf);
|
|
||||||
|
|
||||||
spiResetErrorCounter(MPU9250_SPI_INSTANCE);
|
|
||||||
|
|
||||||
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); //high speed now that we don't need to write to the slow registers
|
|
||||||
|
|
||||||
mpuGyroRead(gyro);
|
|
||||||
|
|
||||||
if ((((int8_t)gyro->gyroADCRaw[1]) == -1 && ((int8_t)gyro->gyroADCRaw[0]) == -1) || spiGetErrorCounter(MPU9250_SPI_INSTANCE) != 0) {
|
|
||||||
spiResetErrorCounter(MPU9250_SPI_INSTANCE);
|
|
||||||
failureMode(FAILURE_GYRO_INIT_FAILED);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void mpu9250SpiAccInit(accDev_t *acc)
|
|
||||||
{
|
|
||||||
acc->acc_1G = 512 * 8;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool verifympu9250WriteRegister(uint8_t reg, uint8_t data)
|
|
||||||
{
|
|
||||||
uint8_t in;
|
|
||||||
uint8_t attemptsRemaining = 20;
|
|
||||||
|
|
||||||
mpu9250WriteRegister(reg, data);
|
|
||||||
delayMicroseconds(100);
|
|
||||||
|
|
||||||
do {
|
|
||||||
mpu9250SlowReadRegister(reg, 1, &in);
|
|
||||||
if (in == data) {
|
|
||||||
return true;
|
|
||||||
} else {
|
|
||||||
debug[3]++;
|
|
||||||
mpu9250WriteRegister(reg, data);
|
|
||||||
delayMicroseconds(100);
|
|
||||||
}
|
|
||||||
} while (attemptsRemaining--);
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
static void mpu9250AccAndGyroInit(uint8_t lpf) {
|
|
||||||
|
|
||||||
if (mpuSpi9250InitDone) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed for writing to slow registers
|
|
||||||
|
|
||||||
mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
|
|
||||||
delay(50);
|
|
||||||
|
|
||||||
verifympu9250WriteRegister(MPU_RA_PWR_MGMT_1, INV_CLK_PLL);
|
|
||||||
|
|
||||||
verifympu9250WriteRegister(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3 | FCB_DISABLED); //Fchoice_b defaults to 00 which makes fchoice 11
|
|
||||||
|
|
||||||
if (lpf == 4) {
|
|
||||||
verifympu9250WriteRegister(MPU_RA_CONFIG, 1); //1KHz, 184DLPF
|
|
||||||
} else if (lpf < 4) {
|
|
||||||
verifympu9250WriteRegister(MPU_RA_CONFIG, 7); //8KHz, 3600DLPF
|
|
||||||
} else if (lpf > 4) {
|
|
||||||
verifympu9250WriteRegister(MPU_RA_CONFIG, 0); //8KHz, 250DLPF
|
|
||||||
}
|
|
||||||
|
|
||||||
verifympu9250WriteRegister(MPU_RA_SMPLRT_DIV, gyroMPU6xxxCalculateDivider()); // Get Divider Drops
|
|
||||||
|
|
||||||
verifympu9250WriteRegister(MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3);
|
|
||||||
verifympu9250WriteRegister(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
|
|
||||||
|
|
||||||
#if defined(USE_MPU_DATA_READY_SIGNAL)
|
|
||||||
verifympu9250WriteRegister(MPU_RA_INT_ENABLE, 0x01); //this resets register MPU_RA_PWR_MGMT_1 and won't read back correctly.
|
|
||||||
#endif
|
|
||||||
|
|
||||||
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST);
|
|
||||||
|
|
||||||
mpuSpi9250InitDone = true; //init done
|
|
||||||
}
|
|
||||||
|
|
||||||
bool mpu9250SpiDetect(void)
|
|
||||||
{
|
|
||||||
uint8_t in;
|
|
||||||
uint8_t attemptsRemaining = 20;
|
|
||||||
|
|
||||||
/* not the best place for this - should really have an init method */
|
|
||||||
#ifdef MPU9250_CS_PIN
|
|
||||||
mpuSpi9250CsPin = IOGetByTag(IO_TAG(MPU9250_CS_PIN));
|
|
||||||
#endif
|
|
||||||
IOInit(mpuSpi9250CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0);
|
|
||||||
IOConfigGPIO(mpuSpi9250CsPin, SPI_IO_CS_CFG);
|
|
||||||
|
|
||||||
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed
|
|
||||||
mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
|
|
||||||
|
|
||||||
do {
|
|
||||||
delay(150);
|
|
||||||
|
|
||||||
mpu9250ReadRegister(MPU_RA_WHO_AM_I, 1, &in);
|
|
||||||
if (in == MPU9250_WHO_AM_I_CONST) {
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
if (!attemptsRemaining) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
} while (attemptsRemaining--);
|
|
||||||
|
|
||||||
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST);
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool mpu9250SpiAccDetect(accDev_t *acc)
|
|
||||||
{
|
|
||||||
if (acc->mpuDetectionResult.sensor != MPU_9250_SPI) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
acc->init = mpu9250SpiAccInit;
|
|
||||||
acc->read = mpuAccRead;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool mpu9250SpiGyroDetect(gyroDev_t *gyro)
|
|
||||||
{
|
|
||||||
if (gyro->mpuDetectionResult.sensor != MPU_9250_SPI) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
gyro->init = mpu9250SpiGyroInit;
|
|
||||||
gyro->read = mpuGyroRead;
|
|
||||||
gyro->intStatus = mpuCheckDataReady;
|
|
||||||
|
|
||||||
// 16.4 dps/lsb scalefactor
|
|
||||||
gyro->scale = 1.0f / 16.4f;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
|
@ -1,36 +0,0 @@
|
||||||
|
|
||||||
#pragma once
|
|
||||||
|
|
||||||
#define mpu9250_CONFIG 0x1A
|
|
||||||
|
|
||||||
/* We should probably use these. :)
|
|
||||||
#define BITS_DLPF_CFG_256HZ 0x00
|
|
||||||
#define BITS_DLPF_CFG_188HZ 0x01
|
|
||||||
#define BITS_DLPF_CFG_98HZ 0x02
|
|
||||||
#define BITS_DLPF_CFG_42HZ 0x03
|
|
||||||
#define BITS_DLPF_CFG_20HZ 0x04
|
|
||||||
#define BITS_DLPF_CFG_10HZ 0x05
|
|
||||||
#define BITS_DLPF_CFG_5HZ 0x06
|
|
||||||
#define BITS_DLPF_CFG_2100HZ_NOLPF 0x07
|
|
||||||
*/
|
|
||||||
|
|
||||||
#define GYRO_SCALE_FACTOR 0.00053292f // (4/131) * pi/180 (32.75 LSB = 1 DPS)
|
|
||||||
|
|
||||||
#define MPU9250_WHO_AM_I_CONST (0x71)
|
|
||||||
|
|
||||||
#define MPU9250_BIT_RESET (0x80)
|
|
||||||
|
|
||||||
// RF = Register Flag
|
|
||||||
#define MPU_RF_DATA_RDY_EN (1 << 0)
|
|
||||||
|
|
||||||
void mpu9250ResetGyro(void);
|
|
||||||
|
|
||||||
bool mpu9250SpiDetect(void);
|
|
||||||
|
|
||||||
bool mpu9250SpiAccDetect(accDev_t *acc);
|
|
||||||
bool mpu9250SpiGyroDetect(gyroDev_t *gyro);
|
|
||||||
|
|
||||||
bool mpu9250WriteRegister(uint8_t reg, uint8_t data);
|
|
||||||
bool verifympu9250WriteRegister(uint8_t reg, uint8_t data);
|
|
||||||
bool mpu9250ReadRegister(uint8_t reg, uint8_t length, uint8_t *data);
|
|
||||||
bool mpu9250SlowReadRegister(uint8_t reg, uint8_t length, uint8_t *data);
|
|
|
@ -42,7 +42,6 @@
|
||||||
#include "accgyro_mpu.h"
|
#include "accgyro_mpu.h"
|
||||||
#include "accgyro_mpu6500.h"
|
#include "accgyro_mpu6500.h"
|
||||||
#include "accgyro_spi_mpu6500.h"
|
#include "accgyro_spi_mpu6500.h"
|
||||||
#include "accgyro_spi_mpu9250.h"
|
|
||||||
#include "compass_ak8963.h"
|
#include "compass_ak8963.h"
|
||||||
|
|
||||||
// This sensor is available in MPU-9250.
|
// This sensor is available in MPU-9250.
|
||||||
|
@ -85,17 +84,7 @@
|
||||||
|
|
||||||
static float magGain[3] = { 1.0f, 1.0f, 1.0f };
|
static float magGain[3] = { 1.0f, 1.0f, 1.0f };
|
||||||
|
|
||||||
// FIXME pretend we have real MPU9250 support
|
#if defined(USE_SPI) && defined(MPU6500_SPI_INSTANCE)
|
||||||
// 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 verifympu9250WriteRegister mpu6500WriteRegister
|
|
||||||
#define mpu9250WriteRegister mpu6500WriteRegister
|
|
||||||
#define mpu9250ReadRegister mpu6500ReadRegister
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
|
|
||||||
|
|
||||||
typedef struct queuedReadState_s {
|
typedef struct queuedReadState_s {
|
||||||
bool waiting;
|
bool waiting;
|
||||||
uint8_t len;
|
uint8_t len;
|
||||||
|
@ -112,22 +101,22 @@ static queuedReadState_t queuedRead = { false, 0, 0};
|
||||||
|
|
||||||
static bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf)
|
static bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf)
|
||||||
{
|
{
|
||||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_ | READ_FLAG); // set I2C slave address for read
|
mpu6500WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_ | READ_FLAG); // set I2C slave address for read
|
||||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
|
mpu6500WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
|
||||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes
|
mpu6500WriteRegister(MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes
|
||||||
delay(10);
|
delay(10);
|
||||||
__disable_irq();
|
__disable_irq();
|
||||||
mpu9250ReadRegister(MPU_RA_EXT_SENS_DATA_00, len_, buf); // read I2C
|
mpu6500ReadRegister(MPU_RA_EXT_SENS_DATA_00, len_, buf); // read I2C
|
||||||
__enable_irq();
|
__enable_irq();
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
|
static bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
|
||||||
{
|
{
|
||||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_); // set I2C slave address for write
|
mpu6500WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_); // set I2C slave address for write
|
||||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
|
mpu6500WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
|
||||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_DO, data); // set I2C salve value
|
mpu6500WriteRegister(MPU_RA_I2C_SLV0_DO, data); // set I2C salve value
|
||||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_CTRL, 0x81); // write 1 byte
|
mpu6500WriteRegister(MPU_RA_I2C_SLV0_CTRL, 0x81); // write 1 byte
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -139,9 +128,9 @@ static bool ak8963SensorStartRead(uint8_t addr_, uint8_t reg_, uint8_t len_)
|
||||||
|
|
||||||
queuedRead.len = len_;
|
queuedRead.len = len_;
|
||||||
|
|
||||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_ | READ_FLAG); // set I2C slave address for read
|
mpu6500WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_ | READ_FLAG); // set I2C slave address for read
|
||||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
|
mpu6500WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register
|
||||||
verifympu9250WriteRegister(MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes
|
mpu6500WriteRegister(MPU_RA_I2C_SLV0_CTRL, len_ | 0x80); // read number of bytes
|
||||||
|
|
||||||
queuedRead.readStartedAt = micros();
|
queuedRead.readStartedAt = micros();
|
||||||
queuedRead.waiting = true;
|
queuedRead.waiting = true;
|
||||||
|
@ -176,7 +165,7 @@ static bool ak8963SensorCompleteRead(uint8_t *buf)
|
||||||
|
|
||||||
queuedRead.waiting = false;
|
queuedRead.waiting = false;
|
||||||
|
|
||||||
mpu9250ReadRegister(MPU_RA_EXT_SENS_DATA_00, queuedRead.len, buf); // read I2C buffer
|
mpu6500ReadRegister(MPU_RA_EXT_SENS_DATA_00, queuedRead.len, buf); // read I2C buffer
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
|
@ -219,7 +208,7 @@ static bool ak8963Init()
|
||||||
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS2, 1, &status);
|
ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_STATUS2, 1, &status);
|
||||||
|
|
||||||
// Trigger first measurement
|
// Trigger first measurement
|
||||||
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
|
#if defined(USE_SPI) && defined(MPU6500_SPI_INSTANCE)
|
||||||
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_CONT1);
|
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_CONT1);
|
||||||
#else
|
#else
|
||||||
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE);
|
ack = ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE);
|
||||||
|
@ -234,7 +223,7 @@ static bool ak8963Read(int16_t *magData)
|
||||||
|
|
||||||
static bool lastReadResult = false;
|
static bool lastReadResult = false;
|
||||||
|
|
||||||
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
|
#if defined(USE_SPI) && defined(MPU6500_SPI_INSTANCE)
|
||||||
static int16_t cachedMagData[3];
|
static int16_t cachedMagData[3];
|
||||||
|
|
||||||
// set magData to latest cached value
|
// set magData to latest cached value
|
||||||
|
@ -316,7 +305,7 @@ restart:
|
||||||
magData[Y] = (int16_t)(buf[3] << 8 | buf[2]) * magGain[Y];
|
magData[Y] = (int16_t)(buf[3] << 8 | buf[2]) * magGain[Y];
|
||||||
magData[Z] = (int16_t)(buf[5] << 8 | buf[4]) * magGain[Z];
|
magData[Z] = (int16_t)(buf[5] << 8 | buf[4]) * magGain[Z];
|
||||||
|
|
||||||
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
|
#if defined(USE_SPI) && defined(MPU6500_SPI_INSTANCE)
|
||||||
// cache mag data for reuse
|
// cache mag data for reuse
|
||||||
memcpy(cachedMagData, magData, sizeof(cachedMagData));
|
memcpy(cachedMagData, magData, sizeof(cachedMagData));
|
||||||
state = CHECK_STATUS;
|
state = CHECK_STATUS;
|
||||||
|
@ -335,16 +324,16 @@ bool ak8963Detect(magDev_t *mag)
|
||||||
bool ack = false;
|
bool ack = false;
|
||||||
uint8_t sig = 0;
|
uint8_t sig = 0;
|
||||||
|
|
||||||
#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE)
|
#if defined(USE_SPI) && defined(MPU6500_SPI_INSTANCE)
|
||||||
// initialze I2C master via SPI bus (MPU9250)
|
// initialze I2C master via SPI bus (MPU9250)
|
||||||
|
|
||||||
ack = verifympu9250WriteRegister(MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR
|
ack = mpu6500WriteRegister(MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR
|
||||||
delay(10);
|
delay(10);
|
||||||
|
|
||||||
ack = verifympu9250WriteRegister(MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz
|
ack = mpu6500WriteRegister(MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz
|
||||||
delay(10);
|
delay(10);
|
||||||
|
|
||||||
ack = verifympu9250WriteRegister(MPU_RA_USER_CTRL, 0x30); // I2C master mode, SPI mode only
|
ack = mpu6500WriteRegister(MPU_RA_USER_CTRL, 0x30); // I2C master mode, SPI mode only
|
||||||
delay(10);
|
delay(10);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -289,7 +289,7 @@ void fcTasksInit(void)
|
||||||
#endif
|
#endif
|
||||||
#ifdef MAG
|
#ifdef MAG
|
||||||
setTaskEnabled(TASK_COMPASS, sensors(SENSOR_MAG));
|
setTaskEnabled(TASK_COMPASS, sensors(SENSOR_MAG));
|
||||||
#if (defined(MPU6500_SPI_INSTANCE) || defined(MPU9250_SPI_INSTANCE)) && defined(USE_MAG_AK8963)
|
#if defined(MPU6500_SPI_INSTANCE) && defined(USE_MAG_AK8963)
|
||||||
// fixme temporary solution for AK6983 via slave I2C on MPU9250
|
// fixme temporary solution for AK6983 via slave I2C on MPU9250
|
||||||
rescheduleTask(TASK_COMPASS, TASK_PERIOD_HZ(40));
|
rescheduleTask(TASK_COMPASS, TASK_PERIOD_HZ(40));
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -230,9 +230,9 @@ static const rxFailsafeChannelMode_e rxFailsafeModesTable[RX_FAILSAFE_TYPE_COUNT
|
||||||
|
|
||||||
/* Sensor names (used in lookup tables for *_hardware settings and in status command output) */
|
/* Sensor names (used in lookup tables for *_hardware settings and in status command output) */
|
||||||
// sync with gyroSensor_e
|
// sync with gyroSensor_e
|
||||||
static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "FAKE"};
|
static const char * const gyroNames[] = { "NONE", "AUTO", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "FAKE"};
|
||||||
// sync with accelerationSensor_e
|
// sync with accelerationSensor_e
|
||||||
static const char * const accNames[] = { "NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "FAKE"};
|
static const char * const accNames[] = { "NONE", "AUTO", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE"};
|
||||||
// sync with baroSensor_e
|
// sync with baroSensor_e
|
||||||
static const char * const baroNames[] = { "NONE", "AUTO", "BMP085", "MS5611", "BMP280", "FAKE"};
|
static const char * const baroNames[] = { "NONE", "AUTO", "BMP085", "MS5611", "BMP280", "FAKE"};
|
||||||
// sync with magSensor_e
|
// sync with magSensor_e
|
||||||
|
|
|
@ -42,7 +42,6 @@
|
||||||
#include "drivers/accgyro_lsm303dlhc.h"
|
#include "drivers/accgyro_lsm303dlhc.h"
|
||||||
#include "drivers/accgyro_spi_mpu6000.h"
|
#include "drivers/accgyro_spi_mpu6000.h"
|
||||||
#include "drivers/accgyro_spi_mpu6500.h"
|
#include "drivers/accgyro_spi_mpu6500.h"
|
||||||
#include "drivers/accgyro_spi_mpu9250.h"
|
|
||||||
#include "drivers/logging.h"
|
#include "drivers/logging.h"
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
|
|
||||||
|
@ -72,13 +71,12 @@ static biquadFilter_t accFilter[XYZ_AXIS_COUNT];
|
||||||
|
|
||||||
static bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse)
|
static bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse)
|
||||||
{
|
{
|
||||||
accelerationSensor_e accHardware;
|
accelerationSensor_e accHardware = ACC_NONE;
|
||||||
|
|
||||||
#ifdef USE_ACC_ADXL345
|
#ifdef USE_ACC_ADXL345
|
||||||
drv_adxl345_config_t acc_params;
|
drv_adxl345_config_t acc_params;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
retry:
|
|
||||||
dev->accAlign = ALIGN_DEFAULT;
|
dev->accAlign = ALIGN_DEFAULT;
|
||||||
|
|
||||||
requestedSensors[SENSOR_INDEX_ACC] = accHardwareToUse;
|
requestedSensors[SENSOR_INDEX_ACC] = accHardwareToUse;
|
||||||
|
@ -206,21 +204,6 @@ retry:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
case ACC_MPU9250:
|
|
||||||
#ifdef USE_ACC_SPI_MPU9250
|
|
||||||
if (mpu9250SpiAccDetect(dev)) {
|
|
||||||
#ifdef ACC_MPU9250_ALIGN
|
|
||||||
dev->accAlign = ACC_MPU9250_ALIGN;
|
|
||||||
#endif
|
|
||||||
accHardware = ACC_MPU9250;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
/* If we are asked for a specific sensor - break out, otherwise - fall through and continue */
|
|
||||||
if (accHardwareToUse != ACC_AUTODETECT) {
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
case ACC_FAKE:
|
case ACC_FAKE:
|
||||||
#ifdef USE_FAKE_ACC
|
#ifdef USE_FAKE_ACC
|
||||||
if (fakeAccDetect(dev)) {
|
if (fakeAccDetect(dev)) {
|
||||||
|
|
|
@ -32,8 +32,7 @@ typedef enum {
|
||||||
ACC_LSM303DLHC = 6,
|
ACC_LSM303DLHC = 6,
|
||||||
ACC_MPU6000 = 7,
|
ACC_MPU6000 = 7,
|
||||||
ACC_MPU6500 = 8,
|
ACC_MPU6500 = 8,
|
||||||
ACC_MPU9250 = 9,
|
ACC_FAKE = 9,
|
||||||
ACC_FAKE = 10,
|
|
||||||
ACC_MAX = ACC_FAKE
|
ACC_MAX = ACC_FAKE
|
||||||
} accelerationSensor_e;
|
} accelerationSensor_e;
|
||||||
|
|
||||||
|
|
|
@ -42,7 +42,6 @@
|
||||||
#include "drivers/accgyro_lsm303dlhc.h"
|
#include "drivers/accgyro_lsm303dlhc.h"
|
||||||
#include "drivers/accgyro_spi_mpu6000.h"
|
#include "drivers/accgyro_spi_mpu6000.h"
|
||||||
#include "drivers/accgyro_spi_mpu6500.h"
|
#include "drivers/accgyro_spi_mpu6500.h"
|
||||||
#include "drivers/accgyro_spi_mpu9250.h"
|
|
||||||
#include "drivers/gyro_sync.h"
|
#include "drivers/gyro_sync.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/logging.h"
|
#include "drivers/logging.h"
|
||||||
|
@ -168,19 +167,6 @@ static bool gyroDetect(gyroDev_t *dev, const extiConfig_t *extiConfig)
|
||||||
#endif
|
#endif
|
||||||
; // fallthrough
|
; // fallthrough
|
||||||
|
|
||||||
case GYRO_MPU9250:
|
|
||||||
#ifdef USE_GYRO_SPI_MPU9250
|
|
||||||
if (mpu9250SpiGyroDetect(dev))
|
|
||||||
{
|
|
||||||
gyroHardware = GYRO_MPU9250;
|
|
||||||
#ifdef GYRO_MPU9250_ALIGN
|
|
||||||
dev->gyroAlign = GYRO_MPU9250_ALIGN;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
; // fallthrough
|
|
||||||
case GYRO_FAKE:
|
case GYRO_FAKE:
|
||||||
#ifdef USE_FAKE_GYRO
|
#ifdef USE_FAKE_GYRO
|
||||||
if (fakeGyroDetect(dev)) {
|
if (fakeGyroDetect(dev)) {
|
||||||
|
@ -209,7 +195,7 @@ bool gyroInit(const gyroConfig_t *gyroConfigToUse)
|
||||||
{
|
{
|
||||||
gyroConfig = gyroConfigToUse;
|
gyroConfig = gyroConfigToUse;
|
||||||
memset(&gyro, 0, sizeof(gyro));
|
memset(&gyro, 0, sizeof(gyro));
|
||||||
#if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250)
|
#if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_ACC_MPU6050)
|
||||||
const extiConfig_t *extiConfig = selectMPUIntExtiConfig();
|
const extiConfig_t *extiConfig = selectMPUIntExtiConfig();
|
||||||
mpuDetect(&gyro.dev);
|
mpuDetect(&gyro.dev);
|
||||||
mpuReset = gyro.dev.mpuConfiguration.reset;
|
mpuReset = gyro.dev.mpuConfiguration.reset;
|
||||||
|
|
|
@ -29,7 +29,6 @@ typedef enum {
|
||||||
GYRO_L3GD20,
|
GYRO_L3GD20,
|
||||||
GYRO_MPU6000,
|
GYRO_MPU6000,
|
||||||
GYRO_MPU6500,
|
GYRO_MPU6500,
|
||||||
GYRO_MPU9250,
|
|
||||||
GYRO_FAKE
|
GYRO_FAKE
|
||||||
} gyroSensor_e;
|
} gyroSensor_e;
|
||||||
|
|
||||||
|
|
|
@ -40,18 +40,19 @@
|
||||||
#define USE_MPU_DATA_READY_SIGNAL
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||||
|
|
||||||
#define MPU9250_CS_PIN PC4
|
#define MPU6500_CS_PIN PC4
|
||||||
#define MPU9250_SPI_INSTANCE SPI1
|
#define MPU6500_SPI_INSTANCE SPI1
|
||||||
|
|
||||||
#define GYRO
|
#define GYRO
|
||||||
#define USE_GYRO_SPI_MPU9250
|
#define USE_GYRO_SPI_MPU6500
|
||||||
#define GYRO_MPU9250_ALIGN CW270_DEG
|
#define GYRO_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define ACC
|
#define ACC
|
||||||
#define USE_ACC_SPI_MPU9250
|
#define USE_ACC_SPI_MPU6500
|
||||||
#define ACC_MPU9250_ALIGN CW270_DEG
|
#define ACC_MPU6500_ALIGN CW270_DEG
|
||||||
|
|
||||||
#define MAG
|
#define MAG
|
||||||
|
#define USE_MPU9250_MAG
|
||||||
#define USE_MAG_AK8963
|
#define USE_MAG_AK8963
|
||||||
#define USE_MAG_AK8975
|
#define USE_MAG_AK8975
|
||||||
#define USE_MAG_HMC5883
|
#define USE_MAG_HMC5883
|
||||||
|
|
|
@ -2,7 +2,9 @@ F405_TARGETS += $(TARGET)
|
||||||
FEATURES += VCP ONBOARDFLASH
|
FEATURES += VCP ONBOARDFLASH
|
||||||
|
|
||||||
TARGET_SRC = \
|
TARGET_SRC = \
|
||||||
drivers/accgyro_spi_mpu9250.c \
|
drivers/accgyro_mpu.c \
|
||||||
|
drivers/accgyro_mpu6500.c \
|
||||||
|
drivers/accgyro_spi_mpu6500.c \
|
||||||
drivers/barometer_bmp085.c \
|
drivers/barometer_bmp085.c \
|
||||||
drivers/barometer_bmp280.c \
|
drivers/barometer_bmp280.c \
|
||||||
drivers/barometer_ms5611.c \
|
drivers/barometer_ms5611.c \
|
||||||
|
|
|
@ -53,9 +53,6 @@
|
||||||
#define MPU6500_CS_PIN SPI2_NSS_PIN
|
#define MPU6500_CS_PIN SPI2_NSS_PIN
|
||||||
#define MPU6500_SPI_INSTANCE SPI2
|
#define MPU6500_SPI_INSTANCE SPI2
|
||||||
#define GYRO_MPU6500_ALIGN CW270_DEG_FLIP
|
#define GYRO_MPU6500_ALIGN CW270_DEG_FLIP
|
||||||
#define USE_GYRO_SPI_MPU9250
|
|
||||||
#define MPU9250_CS_PIN SPI2_NSS_PIN
|
|
||||||
#define MPU9250_SPI_INSTANCE SPI2
|
|
||||||
|
|
||||||
#define ACC
|
#define ACC
|
||||||
#define USE_FAKE_ACC
|
#define USE_FAKE_ACC
|
||||||
|
@ -68,8 +65,6 @@
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define USE_ACC_MPU6500
|
#define USE_ACC_MPU6500
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
#define USE_ACC_MPU9250
|
|
||||||
#define USE_ACC_SPI_MPU9250
|
|
||||||
#define ACC_MPU6500_ALIGN CW270_DEG_FLIP
|
#define ACC_MPU6500_ALIGN CW270_DEG_FLIP
|
||||||
|
|
||||||
#define BARO
|
#define BARO
|
||||||
|
|
|
@ -15,7 +15,6 @@ TARGET_SRC = \
|
||||||
drivers/accgyro_mpu6500.c \
|
drivers/accgyro_mpu6500.c \
|
||||||
drivers/accgyro_spi_mpu6000.c \
|
drivers/accgyro_spi_mpu6000.c \
|
||||||
drivers/accgyro_spi_mpu6500.c \
|
drivers/accgyro_spi_mpu6500.c \
|
||||||
drivers/accgyro_spi_mpu9250.c \
|
|
||||||
drivers/barometer_bmp085.c \
|
drivers/barometer_bmp085.c \
|
||||||
drivers/barometer_bmp280.c \
|
drivers/barometer_bmp280.c \
|
||||||
drivers/barometer_fake.c \
|
drivers/barometer_fake.c \
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue