atbetaflight/src/main/drivers/accgyro/accgyro_mpu.c

551 lines
16 KiB
C
Raw Normal View History

/*
2018-04-21 16:22:46 -07:00
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software 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)
2018-04-21 16:22:46 -07:00
* any later version.
*
2018-04-21 16:22:46 -07:00
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
2018-04-21 16:22:46 -07:00
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
2018-04-21 16:22:46 -07:00
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include "platform.h"
#include "build/atomic.h"
#include "build/build_config.h"
#include "build/debug.h"
#include "common/maths.h"
#include "common/utils.h"
2017-07-15 10:32:34 -07:00
#include "drivers/bus.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_spi.h"
#include "drivers/exti.h"
#include "drivers/io.h"
#include "drivers/nvic.h"
#include "drivers/sensor.h"
#include "drivers/system.h"
#include "drivers/time.h"
2017-08-30 00:50:40 -07:00
#include "drivers/accgyro/accgyro.h"
#include "drivers/accgyro/accgyro_mpu3050.h"
#include "drivers/accgyro/accgyro_mpu6050.h"
#include "drivers/accgyro/accgyro_mpu6500.h"
#include "drivers/accgyro/accgyro_spi_bmi160.h"
#include "drivers/accgyro/accgyro_spi_bmi270.h"
2017-09-01 07:57:54 -07:00
#include "drivers/accgyro/accgyro_spi_icm20649.h"
2017-08-30 00:50:40 -07:00
#include "drivers/accgyro/accgyro_spi_icm20689.h"
#include "drivers/accgyro/accgyro_spi_icm426xx.h"
2022-12-08 18:00:50 -08:00
#include "drivers/accgyro/accgyro_spi_lsm6ds3.h"
2022-12-12 00:37:01 -08:00
#include "drivers/accgyro/accgyro_spi_lsm6dsl.h"
#include "drivers/accgyro/accgyro_spi_lsm6dso.h"
2017-08-30 00:50:40 -07:00
#include "drivers/accgyro/accgyro_spi_mpu6000.h"
#include "drivers/accgyro/accgyro_spi_mpu6500.h"
#include "drivers/accgyro/accgyro_spi_mpu9250.h"
2023-02-08 23:43:07 -08:00
#include "drivers/accgyro/accgyro_spi_sh3001.h"
2018-12-01 01:13:45 -08:00
#include "drivers/accgyro/accgyro_spi_l3gd20.h"
2017-08-30 00:50:40 -07:00
#include "drivers/accgyro/accgyro_mpu.h"
2018-05-10 06:25:37 -07:00
#include "pg/pg.h"
#include "pg/gyrodev.h"
#ifndef MPU_ADDRESS
#define MPU_ADDRESS 0x68
#endif
// 1 MHz max SPI frequency during device detection
#define MPU_MAX_SPI_DETECT_CLK_HZ 1000000
#define MPU_INQUIRY_MASK 0x7E
2022-05-05 04:28:02 -07:00
// Allow 100ms before attempting to access SPI bus
#define GYRO_SPI_STARTUP_MS 100
// Need to see at least this many interrupts during initialisation to confirm EXTI connectivity
#define GYRO_EXTI_DETECT_THRESHOLD 1000
2018-05-10 06:25:37 -07:00
#ifdef USE_I2C_GYRO
2016-12-17 16:16:23 -08:00
static void mpu6050FindRevision(gyroDev_t *gyro)
{
// There is a map of revision contained in the android source tree which is quite comprehensive and may help to understand this code
// See https://android.googlesource.com/kernel/msm.git/+/eaf36994a3992b8f918c18e4f7411e8b2320a35f/drivers/misc/mpu6050/mldl_cfg.c
// determine product ID and revision
uint8_t readBuffer[6];
bool ack = busReadRegisterBuffer(&gyro->dev, MPU_RA_XA_OFFS_H, readBuffer, 6);
uint8_t revision = ((readBuffer[5] & 0x01) << 2) | ((readBuffer[3] & 0x01) << 1) | (readBuffer[1] & 0x01);
if (ack && revision) {
// Congrats, these parts are better
if (revision == 1) {
2016-12-17 16:16:23 -08:00
gyro->mpuDetectionResult.resolution = MPU_HALF_RESOLUTION;
} else if (revision == 2) {
2016-12-17 16:16:23 -08:00
gyro->mpuDetectionResult.resolution = MPU_FULL_RESOLUTION;
} else if ((revision == 3) || (revision == 7)) {
2016-12-17 16:16:23 -08:00
gyro->mpuDetectionResult.resolution = MPU_FULL_RESOLUTION;
} else {
failureMode(FAILURE_ACC_INCOMPATIBLE);
}
} else {
uint8_t productId;
ack = busReadRegisterBuffer(&gyro->dev, MPU_RA_PRODUCT_ID, &productId, 1);
revision = productId & 0x0F;
if (!ack || revision == 0) {
failureMode(FAILURE_ACC_INCOMPATIBLE);
} else if (revision == 4) {
2016-12-17 16:16:23 -08:00
gyro->mpuDetectionResult.resolution = MPU_HALF_RESOLUTION;
} else {
2016-12-17 16:16:23 -08:00
gyro->mpuDetectionResult.resolution = MPU_FULL_RESOLUTION;
}
}
}
#endif
/*
* Gyro interrupt service routine
*/
2018-05-10 06:25:37 -07:00
#ifdef USE_GYRO_EXTI
#ifdef USE_SPI_GYRO
// Called in ISR context
// Gyro read has just completed
busStatus_e mpuIntcallback(uint32_t arg)
{
2021-11-01 13:26:47 -07:00
gyroDev_t *gyro = (gyroDev_t *)arg;
int32_t gyroDmaDuration = cmpTimeCycles(getCycleCounter(), gyro->gyroLastEXTI);
if (gyroDmaDuration > gyro->gyroDmaMaxDuration) {
gyro->gyroDmaMaxDuration = gyroDmaDuration;
}
gyro->dataReady = true;
return BUS_READY;
}
static void mpuIntExtiHandler(extiCallbackRec_t *cb)
{
gyroDev_t *gyro = container_of(cb, gyroDev_t, exti);
2022-04-28 12:00:47 -07:00
// Ideally we'd use a timer to capture such information, but unfortunately the port used for EXTI interrupt does
// not have an associated timer
uint32_t nowCycles = getCycleCounter();
int32_t gyroLastPeriod = cmpTimeCycles(nowCycles, gyro->gyroLastEXTI);
// This detects the short (~79us) EXTI interval of an MPU6xxx gyro
if ((gyro->gyroShortPeriod == 0) || (gyroLastPeriod < gyro->gyroShortPeriod)) {
gyro->gyroSyncEXTI = gyro->gyroLastEXTI + gyro->gyroDmaMaxDuration;
}
gyro->gyroLastEXTI = nowCycles;
if (gyro->gyroModeSPI == GYRO_EXTI_INT_DMA) {
spiSequence(&gyro->dev, gyro->segments);
}
gyro->detectedEXTI++;
}
#else
static void mpuIntExtiHandler(extiCallbackRec_t *cb)
{
2016-12-11 04:17:30 -08:00
gyroDev_t *gyro = container_of(cb, gyroDev_t, exti);
gyro->dataReady = true;
}
#endif
static void mpuIntExtiInit(gyroDev_t *gyro)
{
if (gyro->mpuIntExtiTag == IO_TAG_NONE) {
2016-06-27 11:26:02 -07:00
return;
}
const IO_t mpuIntIO = IOGetByTag(gyro->mpuIntExtiTag);
2016-07-09 06:39:39 -07:00
#ifdef ENSURE_MPU_DATA_READY_IS_LOW
2016-06-27 11:26:02 -07:00
uint8_t status = IORead(mpuIntIO);
if (status) {
return;
}
#endif
2018-05-10 06:25:37 -07:00
IOInit(mpuIntIO, OWNER_GYRO_EXTI, 0);
2016-12-11 04:17:30 -08:00
EXTIHandlerInit(&gyro->exti, mpuIntExtiHandler);
EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IN_FLOATING, BETAFLIGHT_EXTI_TRIGGER_RISING);
EXTIEnable(mpuIntIO);
}
2018-11-25 08:47:14 -08:00
#endif // USE_GYRO_EXTI
2016-12-14 06:32:38 -08:00
bool mpuAccRead(accDev_t *acc)
{
uint8_t data[6];
2021-10-22 11:13:05 -07:00
const bool ack = busReadRegisterBuffer(&acc->gyro->dev, acc->gyro->accDataReg, data, 6);
if (!ack) {
return false;
}
2016-12-14 06:32:38 -08:00
acc->ADCRaw[X] = (int16_t)((data[0] << 8) | data[1]);
acc->ADCRaw[Y] = (int16_t)((data[2] << 8) | data[3]);
acc->ADCRaw[Z] = (int16_t)((data[4] << 8) | data[5]);
return true;
}
bool mpuGyroRead(gyroDev_t *gyro)
{
uint8_t data[6];
2021-10-22 11:13:05 -07:00
const bool ack = busReadRegisterBuffer(&gyro->dev, gyro->gyroDataReg, data, 6);
if (!ack) {
return false;
}
gyro->gyroADCRaw[X] = (int16_t)((data[0] << 8) | data[1]);
gyro->gyroADCRaw[Y] = (int16_t)((data[2] << 8) | data[3]);
gyro->gyroADCRaw[Z] = (int16_t)((data[4] << 8) | data[5]);
return true;
}
2018-05-10 06:25:37 -07:00
#ifdef USE_SPI_GYRO
bool mpuAccReadSPI(accDev_t *acc)
{
switch (acc->gyro->gyroModeSPI) {
case GYRO_EXTI_INT:
case GYRO_EXTI_NO_INT:
{
acc->gyro->dev.txBuf[0] = acc->gyro->accDataReg | 0x80;
busSegment_t segments[] = {
{.u.buffers = {NULL, NULL}, 7, true, NULL},
{.u.link = {NULL, NULL}, 0, true, NULL},
};
segments[0].u.buffers.txData = acc->gyro->dev.txBuf;
segments[0].u.buffers.rxData = &acc->gyro->dev.rxBuf[1];
spiSequence(&acc->gyro->dev, &segments[0]);
// Wait for completion
spiWait(&acc->gyro->dev);
// Fall through
FALLTHROUGH;
}
case GYRO_EXTI_INT_DMA:
{
// If read was triggered in interrupt don't bother waiting. The worst that could happen is that we pick
// up an old value.
// This data was read from the gyro, which is the same SPI device as the acc
2022-12-24 03:37:18 -08:00
int16_t *accData = (int16_t *)acc->gyro->dev.rxBuf;
acc->ADCRaw[X] = __builtin_bswap16(accData[1]);
acc->ADCRaw[Y] = __builtin_bswap16(accData[2]);
acc->ADCRaw[Z] = __builtin_bswap16(accData[3]);
break;
}
case GYRO_EXTI_INIT:
default:
break;
}
return true;
}
bool mpuGyroReadSPI(gyroDev_t *gyro)
{
2022-12-24 03:37:18 -08:00
int16_t *gyroData = (int16_t *)gyro->dev.rxBuf;
switch (gyro->gyroModeSPI) {
case GYRO_EXTI_INIT:
{
// Initialise the tx buffer to all 0xff
memset(gyro->dev.txBuf, 0xff, 16);
#ifdef USE_GYRO_EXTI
// Check that minimum number of interrupts have been detected
// We need some offset from the gyro interrupts to ensure sampling after the interrupt
gyro->gyroDmaMaxDuration = 5;
if (gyro->detectedEXTI > GYRO_EXTI_DETECT_THRESHOLD) {
if (spiUseDMA(&gyro->dev)) {
gyro->dev.callbackArg = (uint32_t)gyro;
2021-10-22 11:13:05 -07:00
gyro->dev.txBuf[0] = gyro->accDataReg | 0x80;
gyro->segments[0].len = gyro->gyroDataReg - gyro->accDataReg + 7;
gyro->segments[0].callback = mpuIntcallback;
gyro->segments[0].u.buffers.txData = gyro->dev.txBuf;
gyro->segments[0].u.buffers.rxData = &gyro->dev.rxBuf[1];
gyro->segments[0].negateCS = true;
gyro->gyroModeSPI = GYRO_EXTI_INT_DMA;
} else {
// Interrupts are present, but no DMA
gyro->gyroModeSPI = GYRO_EXTI_INT;
}
} else
#endif
{
gyro->gyroModeSPI = GYRO_EXTI_NO_INT;
}
break;
}
case GYRO_EXTI_INT:
case GYRO_EXTI_NO_INT:
{
gyro->dev.txBuf[0] = gyro->gyroDataReg | 0x80;
busSegment_t segments[] = {
{.u.buffers = {NULL, NULL}, 7, true, NULL},
{.u.link = {NULL, NULL}, 0, true, NULL},
};
segments[0].u.buffers.txData = gyro->dev.txBuf;
segments[0].u.buffers.rxData = &gyro->dev.rxBuf[1];
spiSequence(&gyro->dev, &segments[0]);
// Wait for completion
spiWait(&gyro->dev);
gyro->gyroADCRaw[X] = __builtin_bswap16(gyroData[1]);
gyro->gyroADCRaw[Y] = __builtin_bswap16(gyroData[2]);
gyro->gyroADCRaw[Z] = __builtin_bswap16(gyroData[3]);
break;
}
case GYRO_EXTI_INT_DMA:
{
2021-10-22 11:13:05 -07:00
// Acc and gyro data may not be continuous (MPU6xxx has temperature in between)
2021-12-28 13:56:45 -08:00
const uint8_t gyroDataIndex = ((gyro->gyroDataReg - gyro->accDataReg) >> 1) + 1;
2021-10-22 11:13:05 -07:00
// If read was triggered in interrupt don't bother waiting. The worst that could happen is that we pick
// up an old value.
2021-12-28 13:56:45 -08:00
gyro->gyroADCRaw[X] = __builtin_bswap16(gyroData[gyroDataIndex]);
gyro->gyroADCRaw[Y] = __builtin_bswap16(gyroData[gyroDataIndex + 1]);
gyro->gyroADCRaw[Z] = __builtin_bswap16(gyroData[gyroDataIndex + 2]);
break;
}
default:
break;
}
return true;
}
typedef uint8_t (*gyroSpiDetectFn_t)(const extDevice_t *dev);
2018-05-10 06:25:37 -07:00
static gyroSpiDetectFn_t gyroSpiDetectFnTable[] = {
#ifdef USE_GYRO_SPI_MPU6000
2018-05-10 06:25:37 -07:00
mpu6000SpiDetect,
2017-03-07 01:01:16 -08:00
#endif
#ifdef USE_GYRO_SPI_MPU6500
2018-05-10 06:25:37 -07:00
mpu6500SpiDetect, // some targets using MPU_9250_SPI, ICM_20608_SPI or ICM_20602_SPI state sensor is MPU_65xx_SPI
2017-07-12 06:40:08 -07:00
#endif
#ifdef USE_GYRO_SPI_MPU9250
2018-05-10 06:25:37 -07:00
mpu9250SpiDetect,
#endif
#ifdef USE_GYRO_SPI_ICM20689
2018-05-10 06:25:37 -07:00
icm20689SpiDetect, // icm20689SpiDetect detects ICM20602 and ICM20689
2017-07-12 06:40:08 -07:00
#endif
2022-12-08 18:00:50 -08:00
#ifdef USE_ACCGYRO_LSM6DS3
lsm6ds3Detect,
#endif
2022-12-12 00:37:01 -08:00
#ifdef USE_ACCGYRO_LSM6DSL
lsm6dslDetect,
#endif
#ifdef USE_ACCGYRO_LSM6DSO
lsm6dsoDetect,
#endif
2023-02-08 23:43:07 -08:00
#ifdef USE_ACCGYRO_SH3001
sh3001Detect,
#endif
#ifdef USE_ACCGYRO_BMI160
bmi160Detect,
#endif
#ifdef USE_ACCGYRO_BMI270
bmi270Detect,
#endif
#if defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P)
icm426xxSpiDetect,
#endif
#ifdef USE_GYRO_SPI_ICM20649
icm20649SpiDetect,
2018-12-01 01:13:45 -08:00
#endif
#ifdef USE_GYRO_L3GD20
l3gd20Detect,
2017-07-12 06:40:08 -07:00
#endif
2018-05-10 06:25:37 -07:00
NULL // Avoid an empty array
};
static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro, const gyroDeviceConfig_t *config)
{
if (!config->csnTag || !spiSetBusInstance(&gyro->dev, config->spiBus)) {
2018-09-15 11:09:45 -07:00
return false;
}
gyro->dev.busType_u.spi.csnPin = IOGetByTag(config->csnTag);
IOInit(gyro->dev.busType_u.spi.csnPin, OWNER_GYRO_CS, RESOURCE_INDEX(config->index));
IOConfigGPIO(gyro->dev.busType_u.spi.csnPin, SPI_IO_CS_CFG);
IOHi(gyro->dev.busType_u.spi.csnPin); // Ensure device is disabled, important when two devices are on the same bus.
2018-05-10 06:25:37 -07:00
uint8_t sensor = MPU_NONE;
2022-05-05 04:28:02 -07:00
// Allow 100ms before attempting to access gyro's SPI bus
// Do this once here rather than in each detection routine to speed boot
while (millis() < GYRO_SPI_STARTUP_MS);
// Set a slow SPI clock that all potential devices can handle during gyro detection
spiSetClkDivisor(&gyro->dev, spiCalculateDivider(MPU_MAX_SPI_DETECT_CLK_HZ));
2018-05-10 06:25:37 -07:00
// It is hard to use hardware to optimize the detection loop here,
// as hardware type and detection function name doesn't match.
// May need a bitmap of hardware to detection function to do it right?
for (size_t index = 0 ; gyroSpiDetectFnTable[index] ; index++) {
sensor = (gyroSpiDetectFnTable[index])(&gyro->dev);
2018-05-10 06:25:37 -07:00
if (sensor != MPU_NONE) {
gyro->mpuDetectionResult.sensor = sensor;
busDeviceRegister(&gyro->dev);
2018-05-10 06:25:37 -07:00
return true;
}
}
2018-05-10 06:25:37 -07:00
2019-04-10 11:16:23 -07:00
// Detection failed, disable CS pin again
2018-12-09 11:42:41 -08:00
spiPreinitByTag(config->csnTag);
2019-04-10 11:16:23 -07:00
return false;
}
#endif
2018-12-09 11:42:41 -08:00
void mpuPreInit(const struct gyroDeviceConfig_s *config)
{
#ifdef USE_SPI_GYRO
spiPreinitRegister(config->csnTag, IOCFG_IPU, 1);
#else
UNUSED(config);
#endif
}
bool mpuDetect(gyroDev_t *gyro, const gyroDeviceConfig_t *config)
{
static busDevice_t bus;
gyro->dev.bus = &bus;
// MPU datasheet specifies 30ms.
delay(35);
if (config->busType == BUS_TYPE_NONE) {
return false;
2018-05-10 06:25:37 -07:00
}
if (config->busType == BUS_TYPE_GYRO_AUTO) {
gyro->dev.bus->busType = BUS_TYPE_I2C;
2018-05-10 06:25:37 -07:00
} else {
gyro->dev.bus->busType = config->busType;
}
2018-05-10 06:25:37 -07:00
#ifdef USE_I2C_GYRO
if (gyro->dev.bus->busType == BUS_TYPE_I2C) {
gyro->dev.bus->busType_u.i2c.device = I2C_CFG_TO_DEV(config->i2cBus);
gyro->dev.busType_u.i2c.address = config->i2cAddress ? config->i2cAddress : MPU_ADDRESS;
uint8_t sig = 0;
bool ack = busReadRegisterBuffer(&gyro->dev, MPU_RA_WHO_AM_I, &sig, 1);
if (ack) {
busDeviceRegister(&gyro->dev);
// If an MPU3050 is connected sig will contain 0.
uint8_t inquiryResult;
ack = busReadRegisterBuffer(&gyro->dev, MPU_RA_WHO_AM_I_LEGACY, &inquiryResult, 1);
inquiryResult &= MPU_INQUIRY_MASK;
if (ack && inquiryResult == MPUx0x0_WHO_AM_I_CONST) {
gyro->mpuDetectionResult.sensor = MPU_3050;
return true;
}
sig &= MPU_INQUIRY_MASK;
if (sig == MPUx0x0_WHO_AM_I_CONST) {
gyro->mpuDetectionResult.sensor = MPU_60x0;
mpu6050FindRevision(gyro);
} else if (sig == MPU6500_WHO_AM_I_CONST) {
gyro->mpuDetectionResult.sensor = MPU_65xx_I2C;
}
return true;
}
}
#endif
2018-05-10 06:25:37 -07:00
#ifdef USE_SPI_GYRO
gyro->dev.bus->busType = BUS_TYPE_SPI;
return detectSPISensorsAndUpdateDetectionResult(gyro, config);
#else
return false;
#endif
}
void mpuGyroInit(gyroDev_t *gyro)
{
2021-10-22 11:13:05 -07:00
gyro->accDataReg = MPU_RA_ACCEL_XOUT_H;
gyro->gyroDataReg = MPU_RA_GYRO_XOUT_H;
2018-05-10 06:25:37 -07:00
#ifdef USE_GYRO_EXTI
mpuIntExtiInit(gyro);
#else
UNUSED(gyro);
#endif
}
Rework gyro sample rate and DLPF configuration and expose additional filter cutoffs (#5483) The old gyro_lpf setting was based on the DLPF_CFG values for the MPU6050 gyro and the enumeration was inaccurate and misleading. For example, the default "OFF" setting did not disable the DLPF, but actually set it to around 250hz. The actual cutoff frequency for each setting varies by gyro hardware so the literal frequencies in the enumeration were also incorrect. Removed gyro_lpf and replaced it with gyro_hardware_lpf (8KHz) and gyro_32khz_hardware_lpf (32KHz). The parameters were renamed to indicate that they are hardware filtering options to differentiate from the many software lowpass filtering options. gyro_hardware_lpf - This parameter sets the filtering and sample rate options for 8KHz gyros (or 32KHz capable gyros running in 8KHz mode). - NORMAL - default setting that is equivalent to the previous "OFF" setting. Configures 8KHz sampling with ~250Hz filter cutoff. - EXPERIMENTAL - 8KHz sampling with a higher frequency filter cutoff (around 3000hz). Considerably more noisy and requires additional software filtering. Note that for the MPU6000 Invensense doesn't officially document the filter cutoff frequency for this selection and simply lists it as "reserved". In testing it's clear that a higher frequency filter cutoff is being selected due to the increased noise, but the actual cutoff frequency is unknown. - 1KHZ_SAMPLING - 1KHz sample rate with and approximate 188Hz filter cutoff. Note that the following additional 1KHz sample rate options with lower filter cutoffs have been eliminated - "98HZ", "42HZ", "20HZ", "10HZ", "5HZ". It seems unlikely that these are still needed are probably no longer viable and flight performance would be very poor. gyro_32khz_hardware_lpf - This parameter sets the filtering options while running in 32KHz mode on capable gyros. It also exposes a new high frequency filter cutoff mode. - NORMAL - The default and matches the current settings used for 32KHz mode. Provides a filter cutoff around 3000Hz. - EXPERIMENTAL - Selects a filter cutoff around 8000Hz. This is a very noisy setting and will require substantial software filtering. The default values for both 8KHz and 32KHz sample rates were chosen to match the previous defaults and users should not experience any performance differences. Normalized the gyro initialization. Previously there was little consistency on how the initialization was performed and the settings interpreted. For example, MPU9250 used a completely different logic tree when configuring the registers. Disconnected the literal parameter value from the gyro initialization. The gyro_lpf parameter contained a number from 0-7 that was literally applied to the configuration register during the gyro initialization. This caused some older gyro initializations to be incorrect as they used a different register layout (MPU3050 and L3G4200D). By transitioning to a logical selection the actual value applied to the hardware register is abstracted. This will better future-proof the design as new gyros may have a different register structure that may be incompatible with the old method. Added a gyroregisters command to the CLI that is used to read the current register settings from the gyro and dump them to the CLI. This is used to verify the configuration in comparison to the datasheets for the various gyros. Testing empirically by looking at the relative noise from the gyros can give a rough estimate whether the different options are selecting correctly, but it's not very precise. The code for the gyroregisters CLI command is wrapped inside #ifdef USE_GYRO_REGISTER_DUMP blocks to allow easy disabling. It's currently enabled for all targets but we may decide to disable before release or only limit to targets with more available space (>=F4).
2018-03-21 18:02:30 -07:00
uint8_t mpuGyroDLPF(gyroDev_t *gyro)
{
uint8_t ret = 0;
// If gyro is in 32KHz mode then the DLPF bits aren't used
if (gyro->gyroRateKHz <= GYRO_RATE_8_kHz) {
Rework gyro sample rate and DLPF configuration and expose additional filter cutoffs (#5483) The old gyro_lpf setting was based on the DLPF_CFG values for the MPU6050 gyro and the enumeration was inaccurate and misleading. For example, the default "OFF" setting did not disable the DLPF, but actually set it to around 250hz. The actual cutoff frequency for each setting varies by gyro hardware so the literal frequencies in the enumeration were also incorrect. Removed gyro_lpf and replaced it with gyro_hardware_lpf (8KHz) and gyro_32khz_hardware_lpf (32KHz). The parameters were renamed to indicate that they are hardware filtering options to differentiate from the many software lowpass filtering options. gyro_hardware_lpf - This parameter sets the filtering and sample rate options for 8KHz gyros (or 32KHz capable gyros running in 8KHz mode). - NORMAL - default setting that is equivalent to the previous "OFF" setting. Configures 8KHz sampling with ~250Hz filter cutoff. - EXPERIMENTAL - 8KHz sampling with a higher frequency filter cutoff (around 3000hz). Considerably more noisy and requires additional software filtering. Note that for the MPU6000 Invensense doesn't officially document the filter cutoff frequency for this selection and simply lists it as "reserved". In testing it's clear that a higher frequency filter cutoff is being selected due to the increased noise, but the actual cutoff frequency is unknown. - 1KHZ_SAMPLING - 1KHz sample rate with and approximate 188Hz filter cutoff. Note that the following additional 1KHz sample rate options with lower filter cutoffs have been eliminated - "98HZ", "42HZ", "20HZ", "10HZ", "5HZ". It seems unlikely that these are still needed are probably no longer viable and flight performance would be very poor. gyro_32khz_hardware_lpf - This parameter sets the filtering options while running in 32KHz mode on capable gyros. It also exposes a new high frequency filter cutoff mode. - NORMAL - The default and matches the current settings used for 32KHz mode. Provides a filter cutoff around 3000Hz. - EXPERIMENTAL - Selects a filter cutoff around 8000Hz. This is a very noisy setting and will require substantial software filtering. The default values for both 8KHz and 32KHz sample rates were chosen to match the previous defaults and users should not experience any performance differences. Normalized the gyro initialization. Previously there was little consistency on how the initialization was performed and the settings interpreted. For example, MPU9250 used a completely different logic tree when configuring the registers. Disconnected the literal parameter value from the gyro initialization. The gyro_lpf parameter contained a number from 0-7 that was literally applied to the configuration register during the gyro initialization. This caused some older gyro initializations to be incorrect as they used a different register layout (MPU3050 and L3G4200D). By transitioning to a logical selection the actual value applied to the hardware register is abstracted. This will better future-proof the design as new gyros may have a different register structure that may be incompatible with the old method. Added a gyroregisters command to the CLI that is used to read the current register settings from the gyro and dump them to the CLI. This is used to verify the configuration in comparison to the datasheets for the various gyros. Testing empirically by looking at the relative noise from the gyros can give a rough estimate whether the different options are selecting correctly, but it's not very precise. The code for the gyroregisters CLI command is wrapped inside #ifdef USE_GYRO_REGISTER_DUMP blocks to allow easy disabling. It's currently enabled for all targets but we may decide to disable before release or only limit to targets with more available space (>=F4).
2018-03-21 18:02:30 -07:00
switch (gyro->hardware_lpf) {
#ifdef USE_GYRO_DLPF_EXPERIMENTAL
Rework gyro sample rate and DLPF configuration and expose additional filter cutoffs (#5483) The old gyro_lpf setting was based on the DLPF_CFG values for the MPU6050 gyro and the enumeration was inaccurate and misleading. For example, the default "OFF" setting did not disable the DLPF, but actually set it to around 250hz. The actual cutoff frequency for each setting varies by gyro hardware so the literal frequencies in the enumeration were also incorrect. Removed gyro_lpf and replaced it with gyro_hardware_lpf (8KHz) and gyro_32khz_hardware_lpf (32KHz). The parameters were renamed to indicate that they are hardware filtering options to differentiate from the many software lowpass filtering options. gyro_hardware_lpf - This parameter sets the filtering and sample rate options for 8KHz gyros (or 32KHz capable gyros running in 8KHz mode). - NORMAL - default setting that is equivalent to the previous "OFF" setting. Configures 8KHz sampling with ~250Hz filter cutoff. - EXPERIMENTAL - 8KHz sampling with a higher frequency filter cutoff (around 3000hz). Considerably more noisy and requires additional software filtering. Note that for the MPU6000 Invensense doesn't officially document the filter cutoff frequency for this selection and simply lists it as "reserved". In testing it's clear that a higher frequency filter cutoff is being selected due to the increased noise, but the actual cutoff frequency is unknown. - 1KHZ_SAMPLING - 1KHz sample rate with and approximate 188Hz filter cutoff. Note that the following additional 1KHz sample rate options with lower filter cutoffs have been eliminated - "98HZ", "42HZ", "20HZ", "10HZ", "5HZ". It seems unlikely that these are still needed are probably no longer viable and flight performance would be very poor. gyro_32khz_hardware_lpf - This parameter sets the filtering options while running in 32KHz mode on capable gyros. It also exposes a new high frequency filter cutoff mode. - NORMAL - The default and matches the current settings used for 32KHz mode. Provides a filter cutoff around 3000Hz. - EXPERIMENTAL - Selects a filter cutoff around 8000Hz. This is a very noisy setting and will require substantial software filtering. The default values for both 8KHz and 32KHz sample rates were chosen to match the previous defaults and users should not experience any performance differences. Normalized the gyro initialization. Previously there was little consistency on how the initialization was performed and the settings interpreted. For example, MPU9250 used a completely different logic tree when configuring the registers. Disconnected the literal parameter value from the gyro initialization. The gyro_lpf parameter contained a number from 0-7 that was literally applied to the configuration register during the gyro initialization. This caused some older gyro initializations to be incorrect as they used a different register layout (MPU3050 and L3G4200D). By transitioning to a logical selection the actual value applied to the hardware register is abstracted. This will better future-proof the design as new gyros may have a different register structure that may be incompatible with the old method. Added a gyroregisters command to the CLI that is used to read the current register settings from the gyro and dump them to the CLI. This is used to verify the configuration in comparison to the datasheets for the various gyros. Testing empirically by looking at the relative noise from the gyros can give a rough estimate whether the different options are selecting correctly, but it's not very precise. The code for the gyroregisters CLI command is wrapped inside #ifdef USE_GYRO_REGISTER_DUMP blocks to allow easy disabling. It's currently enabled for all targets but we may decide to disable before release or only limit to targets with more available space (>=F4).
2018-03-21 18:02:30 -07:00
case GYRO_HARDWARE_LPF_EXPERIMENTAL:
// experimental mode not supported for MPU60x0 family
if ((gyro->gyroHardware != GYRO_MPU6050) && (gyro->gyroHardware != GYRO_MPU6000)) {
ret = 7;
} else {
ret = 0;
}
Rework gyro sample rate and DLPF configuration and expose additional filter cutoffs (#5483) The old gyro_lpf setting was based on the DLPF_CFG values for the MPU6050 gyro and the enumeration was inaccurate and misleading. For example, the default "OFF" setting did not disable the DLPF, but actually set it to around 250hz. The actual cutoff frequency for each setting varies by gyro hardware so the literal frequencies in the enumeration were also incorrect. Removed gyro_lpf and replaced it with gyro_hardware_lpf (8KHz) and gyro_32khz_hardware_lpf (32KHz). The parameters were renamed to indicate that they are hardware filtering options to differentiate from the many software lowpass filtering options. gyro_hardware_lpf - This parameter sets the filtering and sample rate options for 8KHz gyros (or 32KHz capable gyros running in 8KHz mode). - NORMAL - default setting that is equivalent to the previous "OFF" setting. Configures 8KHz sampling with ~250Hz filter cutoff. - EXPERIMENTAL - 8KHz sampling with a higher frequency filter cutoff (around 3000hz). Considerably more noisy and requires additional software filtering. Note that for the MPU6000 Invensense doesn't officially document the filter cutoff frequency for this selection and simply lists it as "reserved". In testing it's clear that a higher frequency filter cutoff is being selected due to the increased noise, but the actual cutoff frequency is unknown. - 1KHZ_SAMPLING - 1KHz sample rate with and approximate 188Hz filter cutoff. Note that the following additional 1KHz sample rate options with lower filter cutoffs have been eliminated - "98HZ", "42HZ", "20HZ", "10HZ", "5HZ". It seems unlikely that these are still needed are probably no longer viable and flight performance would be very poor. gyro_32khz_hardware_lpf - This parameter sets the filtering options while running in 32KHz mode on capable gyros. It also exposes a new high frequency filter cutoff mode. - NORMAL - The default and matches the current settings used for 32KHz mode. Provides a filter cutoff around 3000Hz. - EXPERIMENTAL - Selects a filter cutoff around 8000Hz. This is a very noisy setting and will require substantial software filtering. The default values for both 8KHz and 32KHz sample rates were chosen to match the previous defaults and users should not experience any performance differences. Normalized the gyro initialization. Previously there was little consistency on how the initialization was performed and the settings interpreted. For example, MPU9250 used a completely different logic tree when configuring the registers. Disconnected the literal parameter value from the gyro initialization. The gyro_lpf parameter contained a number from 0-7 that was literally applied to the configuration register during the gyro initialization. This caused some older gyro initializations to be incorrect as they used a different register layout (MPU3050 and L3G4200D). By transitioning to a logical selection the actual value applied to the hardware register is abstracted. This will better future-proof the design as new gyros may have a different register structure that may be incompatible with the old method. Added a gyroregisters command to the CLI that is used to read the current register settings from the gyro and dump them to the CLI. This is used to verify the configuration in comparison to the datasheets for the various gyros. Testing empirically by looking at the relative noise from the gyros can give a rough estimate whether the different options are selecting correctly, but it's not very precise. The code for the gyroregisters CLI command is wrapped inside #ifdef USE_GYRO_REGISTER_DUMP blocks to allow easy disabling. It's currently enabled for all targets but we may decide to disable before release or only limit to targets with more available space (>=F4).
2018-03-21 18:02:30 -07:00
break;
#endif
case GYRO_HARDWARE_LPF_NORMAL:
default:
ret = 0;
break;
Rework gyro sample rate and DLPF configuration and expose additional filter cutoffs (#5483) The old gyro_lpf setting was based on the DLPF_CFG values for the MPU6050 gyro and the enumeration was inaccurate and misleading. For example, the default "OFF" setting did not disable the DLPF, but actually set it to around 250hz. The actual cutoff frequency for each setting varies by gyro hardware so the literal frequencies in the enumeration were also incorrect. Removed gyro_lpf and replaced it with gyro_hardware_lpf (8KHz) and gyro_32khz_hardware_lpf (32KHz). The parameters were renamed to indicate that they are hardware filtering options to differentiate from the many software lowpass filtering options. gyro_hardware_lpf - This parameter sets the filtering and sample rate options for 8KHz gyros (or 32KHz capable gyros running in 8KHz mode). - NORMAL - default setting that is equivalent to the previous "OFF" setting. Configures 8KHz sampling with ~250Hz filter cutoff. - EXPERIMENTAL - 8KHz sampling with a higher frequency filter cutoff (around 3000hz). Considerably more noisy and requires additional software filtering. Note that for the MPU6000 Invensense doesn't officially document the filter cutoff frequency for this selection and simply lists it as "reserved". In testing it's clear that a higher frequency filter cutoff is being selected due to the increased noise, but the actual cutoff frequency is unknown. - 1KHZ_SAMPLING - 1KHz sample rate with and approximate 188Hz filter cutoff. Note that the following additional 1KHz sample rate options with lower filter cutoffs have been eliminated - "98HZ", "42HZ", "20HZ", "10HZ", "5HZ". It seems unlikely that these are still needed are probably no longer viable and flight performance would be very poor. gyro_32khz_hardware_lpf - This parameter sets the filtering options while running in 32KHz mode on capable gyros. It also exposes a new high frequency filter cutoff mode. - NORMAL - The default and matches the current settings used for 32KHz mode. Provides a filter cutoff around 3000Hz. - EXPERIMENTAL - Selects a filter cutoff around 8000Hz. This is a very noisy setting and will require substantial software filtering. The default values for both 8KHz and 32KHz sample rates were chosen to match the previous defaults and users should not experience any performance differences. Normalized the gyro initialization. Previously there was little consistency on how the initialization was performed and the settings interpreted. For example, MPU9250 used a completely different logic tree when configuring the registers. Disconnected the literal parameter value from the gyro initialization. The gyro_lpf parameter contained a number from 0-7 that was literally applied to the configuration register during the gyro initialization. This caused some older gyro initializations to be incorrect as they used a different register layout (MPU3050 and L3G4200D). By transitioning to a logical selection the actual value applied to the hardware register is abstracted. This will better future-proof the design as new gyros may have a different register structure that may be incompatible with the old method. Added a gyroregisters command to the CLI that is used to read the current register settings from the gyro and dump them to the CLI. This is used to verify the configuration in comparison to the datasheets for the various gyros. Testing empirically by looking at the relative noise from the gyros can give a rough estimate whether the different options are selecting correctly, but it's not very precise. The code for the gyroregisters CLI command is wrapped inside #ifdef USE_GYRO_REGISTER_DUMP blocks to allow easy disabling. It's currently enabled for all targets but we may decide to disable before release or only limit to targets with more available space (>=F4).
2018-03-21 18:02:30 -07:00
}
}
return ret;
}
#ifdef USE_GYRO_REGISTER_DUMP
uint8_t mpuGyroReadRegister(const extDevice_t *dev, uint8_t reg)
Rework gyro sample rate and DLPF configuration and expose additional filter cutoffs (#5483) The old gyro_lpf setting was based on the DLPF_CFG values for the MPU6050 gyro and the enumeration was inaccurate and misleading. For example, the default "OFF" setting did not disable the DLPF, but actually set it to around 250hz. The actual cutoff frequency for each setting varies by gyro hardware so the literal frequencies in the enumeration were also incorrect. Removed gyro_lpf and replaced it with gyro_hardware_lpf (8KHz) and gyro_32khz_hardware_lpf (32KHz). The parameters were renamed to indicate that they are hardware filtering options to differentiate from the many software lowpass filtering options. gyro_hardware_lpf - This parameter sets the filtering and sample rate options for 8KHz gyros (or 32KHz capable gyros running in 8KHz mode). - NORMAL - default setting that is equivalent to the previous "OFF" setting. Configures 8KHz sampling with ~250Hz filter cutoff. - EXPERIMENTAL - 8KHz sampling with a higher frequency filter cutoff (around 3000hz). Considerably more noisy and requires additional software filtering. Note that for the MPU6000 Invensense doesn't officially document the filter cutoff frequency for this selection and simply lists it as "reserved". In testing it's clear that a higher frequency filter cutoff is being selected due to the increased noise, but the actual cutoff frequency is unknown. - 1KHZ_SAMPLING - 1KHz sample rate with and approximate 188Hz filter cutoff. Note that the following additional 1KHz sample rate options with lower filter cutoffs have been eliminated - "98HZ", "42HZ", "20HZ", "10HZ", "5HZ". It seems unlikely that these are still needed are probably no longer viable and flight performance would be very poor. gyro_32khz_hardware_lpf - This parameter sets the filtering options while running in 32KHz mode on capable gyros. It also exposes a new high frequency filter cutoff mode. - NORMAL - The default and matches the current settings used for 32KHz mode. Provides a filter cutoff around 3000Hz. - EXPERIMENTAL - Selects a filter cutoff around 8000Hz. This is a very noisy setting and will require substantial software filtering. The default values for both 8KHz and 32KHz sample rates were chosen to match the previous defaults and users should not experience any performance differences. Normalized the gyro initialization. Previously there was little consistency on how the initialization was performed and the settings interpreted. For example, MPU9250 used a completely different logic tree when configuring the registers. Disconnected the literal parameter value from the gyro initialization. The gyro_lpf parameter contained a number from 0-7 that was literally applied to the configuration register during the gyro initialization. This caused some older gyro initializations to be incorrect as they used a different register layout (MPU3050 and L3G4200D). By transitioning to a logical selection the actual value applied to the hardware register is abstracted. This will better future-proof the design as new gyros may have a different register structure that may be incompatible with the old method. Added a gyroregisters command to the CLI that is used to read the current register settings from the gyro and dump them to the CLI. This is used to verify the configuration in comparison to the datasheets for the various gyros. Testing empirically by looking at the relative noise from the gyros can give a rough estimate whether the different options are selecting correctly, but it's not very precise. The code for the gyroregisters CLI command is wrapped inside #ifdef USE_GYRO_REGISTER_DUMP blocks to allow easy disabling. It's currently enabled for all targets but we may decide to disable before release or only limit to targets with more available space (>=F4).
2018-03-21 18:02:30 -07:00
{
uint8_t data;
const bool ack = busReadRegisterBuffer(dev, reg, &data, 1);
Rework gyro sample rate and DLPF configuration and expose additional filter cutoffs (#5483) The old gyro_lpf setting was based on the DLPF_CFG values for the MPU6050 gyro and the enumeration was inaccurate and misleading. For example, the default "OFF" setting did not disable the DLPF, but actually set it to around 250hz. The actual cutoff frequency for each setting varies by gyro hardware so the literal frequencies in the enumeration were also incorrect. Removed gyro_lpf and replaced it with gyro_hardware_lpf (8KHz) and gyro_32khz_hardware_lpf (32KHz). The parameters were renamed to indicate that they are hardware filtering options to differentiate from the many software lowpass filtering options. gyro_hardware_lpf - This parameter sets the filtering and sample rate options for 8KHz gyros (or 32KHz capable gyros running in 8KHz mode). - NORMAL - default setting that is equivalent to the previous "OFF" setting. Configures 8KHz sampling with ~250Hz filter cutoff. - EXPERIMENTAL - 8KHz sampling with a higher frequency filter cutoff (around 3000hz). Considerably more noisy and requires additional software filtering. Note that for the MPU6000 Invensense doesn't officially document the filter cutoff frequency for this selection and simply lists it as "reserved". In testing it's clear that a higher frequency filter cutoff is being selected due to the increased noise, but the actual cutoff frequency is unknown. - 1KHZ_SAMPLING - 1KHz sample rate with and approximate 188Hz filter cutoff. Note that the following additional 1KHz sample rate options with lower filter cutoffs have been eliminated - "98HZ", "42HZ", "20HZ", "10HZ", "5HZ". It seems unlikely that these are still needed are probably no longer viable and flight performance would be very poor. gyro_32khz_hardware_lpf - This parameter sets the filtering options while running in 32KHz mode on capable gyros. It also exposes a new high frequency filter cutoff mode. - NORMAL - The default and matches the current settings used for 32KHz mode. Provides a filter cutoff around 3000Hz. - EXPERIMENTAL - Selects a filter cutoff around 8000Hz. This is a very noisy setting and will require substantial software filtering. The default values for both 8KHz and 32KHz sample rates were chosen to match the previous defaults and users should not experience any performance differences. Normalized the gyro initialization. Previously there was little consistency on how the initialization was performed and the settings interpreted. For example, MPU9250 used a completely different logic tree when configuring the registers. Disconnected the literal parameter value from the gyro initialization. The gyro_lpf parameter contained a number from 0-7 that was literally applied to the configuration register during the gyro initialization. This caused some older gyro initializations to be incorrect as they used a different register layout (MPU3050 and L3G4200D). By transitioning to a logical selection the actual value applied to the hardware register is abstracted. This will better future-proof the design as new gyros may have a different register structure that may be incompatible with the old method. Added a gyroregisters command to the CLI that is used to read the current register settings from the gyro and dump them to the CLI. This is used to verify the configuration in comparison to the datasheets for the various gyros. Testing empirically by looking at the relative noise from the gyros can give a rough estimate whether the different options are selecting correctly, but it's not very precise. The code for the gyroregisters CLI command is wrapped inside #ifdef USE_GYRO_REGISTER_DUMP blocks to allow easy disabling. It's currently enabled for all targets but we may decide to disable before release or only limit to targets with more available space (>=F4).
2018-03-21 18:02:30 -07:00
if (ack) {
return data;
} else {
return 0;
}
}
#endif