Split initialization from gyro.c for flash savings

Move low performance requirements initialization code into gyro_init.c and optimize that for size.
This commit is contained in:
Bruce Luckcuck 2020-03-13 07:30:42 -04:00
parent d733c48b04
commit ad0e7154a7
14 changed files with 859 additions and 775 deletions

View File

@ -126,6 +126,7 @@ COMMON_SRC = \
sensors/boardalignment.c \
sensors/compass.c \
sensors/gyro.c \
sensors/gyro_init.c \
sensors/initialisation.c \
blackbox/blackbox.c \
blackbox/blackbox_encoding.c \
@ -348,7 +349,8 @@ SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
io/spektrum_vtx_control.c \
osd/osd.c \
osd/osd_elements.c \
rx/rx_bind.c
rx/rx_bind.c \
sensors/gyro_init.c
# F4 and F7 optimizations
ifneq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))

View File

@ -164,6 +164,7 @@ bool cliMode = false;
#include "sensors/compass.h"
#include "sensors/esc_sensor.h"
#include "sensors/gyro.h"
#include "sensors/gyro_init.h"
#include "sensors/sensors.h"
#include "telemetry/frsky_hub.h"

View File

@ -164,6 +164,7 @@
#include "sensors/compass.h"
#include "sensors/esc_sensor.h"
#include "sensors/gyro.h"
#include "sensors/gyro_init.h"
#include "sensors/initialisation.h"
#include "telemetry/telemetry.h"

View File

@ -133,6 +133,7 @@
#include "sensors/compass.h"
#include "sensors/esc_sensor.h"
#include "sensors/gyro.h"
#include "sensors/gyro_init.h"
#include "sensors/rangefinder.h"
#include "telemetry/telemetry.h"

View File

@ -80,6 +80,7 @@
#include "sensors/boardalignment.h"
#include "sensors/gyro.h"
#include "sensors/gyro_init.h"
#include "sensors/sensors.h"
#include "acceleration.h"

View File

@ -51,6 +51,7 @@
#include "sensors/boardalignment.h"
#include "sensors/gyro.h"
#include "sensors/gyro_init.h"
#include "sensors/sensors.h"
#include "compass.h"

View File

@ -38,31 +38,6 @@
#include "pg/pg_ids.h"
#include "pg/gyrodev.h"
#include "drivers/accgyro/accgyro.h"
#include "drivers/accgyro/accgyro_fake.h"
#include "drivers/accgyro/accgyro_mpu.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"
#include "drivers/accgyro/accgyro_spi_icm20649.h"
#include "drivers/accgyro/accgyro_spi_icm20689.h"
#include "drivers/accgyro/accgyro_spi_icm20689.h"
#include "drivers/accgyro/accgyro_spi_icm42605.h"
#include "drivers/accgyro/accgyro_spi_mpu6000.h"
#include "drivers/accgyro/accgyro_spi_mpu6500.h"
#include "drivers/accgyro/accgyro_spi_mpu9250.h"
#ifdef USE_GYRO_L3GD20
#include "drivers/accgyro/accgyro_spi_l3gd20.h"
#endif
#ifdef USE_GYRO_L3G4200D
#include "drivers/accgyro_legacy/accgyro_l3g4200d.h"
#endif
#include "drivers/accgyro/gyro_sync.h"
#include "drivers/bus_spi.h"
#include "drivers/io.h"
@ -81,25 +56,19 @@
#include "sensors/boardalignment.h"
#include "sensors/gyro.h"
#include "sensors/sensors.h"
#include "sensors/gyro_init.h"
#if ((TARGET_FLASH_SIZE > 128) && (defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_MPU6500)))
#define USE_GYRO_SLEW_LIMITER
#endif
FAST_RAM_ZERO_INIT gyro_t gyro;
static FAST_RAM_ZERO_INIT uint8_t gyroDebugMode;
static FAST_RAM_ZERO_INIT uint8_t gyroToUse;
static FAST_RAM_ZERO_INIT bool overflowDetected;
#ifdef USE_GYRO_OVERFLOW_CHECK
static FAST_RAM_ZERO_INIT timeUs_t overflowTimeUs;
#endif
#ifdef USE_GYRO_OVERFLOW_CHECK
static FAST_RAM_ZERO_INIT uint8_t overflowAxisMask;
#endif
#ifdef USE_YAW_SPIN_RECOVERY
static FAST_RAM_ZERO_INIT bool yawSpinRecoveryEnabled;
static FAST_RAM_ZERO_INIT int yawSpinRecoveryThreshold;
@ -113,39 +82,15 @@ static FAST_RAM_ZERO_INIT int accumulatedMeasurementCount;
static FAST_RAM_ZERO_INIT int16_t gyroSensorTemperature;
static bool gyroHasOverflowProtection = true;
static FAST_RAM_ZERO_INIT bool useDualGyroDebugging;
static FAST_RAM_ZERO_INIT flight_dynamics_index_t gyroDebugAxis;
FAST_RAM uint8_t activePidLoopDenom = 1;
typedef struct gyroCalibration_s {
float sum[XYZ_AXIS_COUNT];
stdev_t var[XYZ_AXIS_COUNT];
int32_t cyclesRemaining;
} gyroCalibration_t;
static bool firstArmingCalibrationWasStarted = false;
typedef struct gyroSensor_s {
gyroDev_t gyroDev;
gyroCalibration_t calibration;
} gyroSensor_t;
STATIC_UNIT_TESTED FAST_RAM_ZERO_INIT gyroSensor_t gyroSensor1;
#ifdef USE_MULTI_GYRO
STATIC_UNIT_TESTED FAST_RAM_ZERO_INIT gyroSensor_t gyroSensor2;
#endif
static gyroDetectionFlags_t gyroDetectionFlags = NO_GYROS_DETECTED;
#ifdef UNIT_TEST
STATIC_UNIT_TESTED gyroSensor_t * const gyroSensorPtr = &gyroSensor1;
STATIC_UNIT_TESTED gyroDev_t * const gyroDevPtr = &gyroSensor1.gyroDev;
STATIC_UNIT_TESTED gyroSensor_t * const gyroSensorPtr = &gyro.gyroSensor1;
STATIC_UNIT_TESTED gyroDev_t * const gyroDevPtr = &gyro.gyroSensor1.gyroDev;
#endif
static void gyroInitSensorFilters(gyroSensor_t *gyroSensor);
static bool gyroInitLowpassFilterLpf(int slot, int type, uint16_t lpfHz, uint32_t looptime);
#define DEBUG_GYRO_CALIBRATION 3
@ -158,11 +103,6 @@ PG_REGISTER_WITH_RESET_FN(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 8);
#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1
#endif
#ifdef USE_GYRO_DATA_ANALYSE
#define DYNAMIC_NOTCH_DEFAULT_CENTER_HZ 350
#define DYNAMIC_NOTCH_DEFAULT_CUTOFF_HZ 300
#endif
void pgResetFn_gyroConfig(gyroConfig_t *gyroConfig)
{
gyroConfig->gyroCalibrationDuration = 125; // 1.25 seconds
@ -194,624 +134,13 @@ void pgResetFn_gyroConfig(gyroConfig_t *gyroConfig)
gyroConfig->gyro_filter_debug_axis = FD_ROLL;
}
#ifdef USE_MULTI_GYRO
#define ACTIVE_GYRO ((gyroToUse == GYRO_CONFIG_USE_GYRO_2) ? &gyroSensor2 : &gyroSensor1)
#else
#define ACTIVE_GYRO (&gyroSensor1)
#endif
const busDevice_t *gyroSensorBus(void)
{
return &ACTIVE_GYRO->gyroDev.bus;
}
#ifdef USE_GYRO_REGISTER_DUMP
const busDevice_t *gyroSensorBusByDevice(uint8_t whichSensor)
{
#ifdef USE_MULTI_GYRO
if (whichSensor == GYRO_CONFIG_USE_GYRO_2) {
return &gyroSensor2.gyroDev.bus;
}
#else
UNUSED(whichSensor);
#endif
return &gyroSensor1.gyroDev.bus;
}
#endif // USE_GYRO_REGISTER_DUMP
const mpuDetectionResult_t *gyroMpuDetectionResult(void)
{
return &ACTIVE_GYRO->gyroDev.mpuDetectionResult;
}
STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
{
gyroHardware_e gyroHardware = GYRO_DEFAULT;
switch (gyroHardware) {
case GYRO_DEFAULT:
FALLTHROUGH;
#ifdef USE_GYRO_MPU6050
case GYRO_MPU6050:
if (mpu6050GyroDetect(dev)) {
gyroHardware = GYRO_MPU6050;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_L3G4200D
case GYRO_L3G4200D:
if (l3g4200dDetect(dev)) {
gyroHardware = GYRO_L3G4200D;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_MPU3050
case GYRO_MPU3050:
if (mpu3050Detect(dev)) {
gyroHardware = GYRO_MPU3050;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_L3GD20
case GYRO_L3GD20:
if (l3gd20GyroDetect(dev)) {
gyroHardware = GYRO_L3GD20;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_SPI_MPU6000
case GYRO_MPU6000:
if (mpu6000SpiGyroDetect(dev)) {
gyroHardware = GYRO_MPU6000;
break;
}
FALLTHROUGH;
#endif
#if defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500)
case GYRO_MPU6500:
case GYRO_ICM20601:
case GYRO_ICM20602:
case GYRO_ICM20608G:
#ifdef USE_GYRO_SPI_MPU6500
if (mpu6500GyroDetect(dev) || mpu6500SpiGyroDetect(dev)) {
#else
if (mpu6500GyroDetect(dev)) {
#endif
switch (dev->mpuDetectionResult.sensor) {
case MPU_9250_SPI:
gyroHardware = GYRO_MPU9250;
break;
case ICM_20601_SPI:
gyroHardware = GYRO_ICM20601;
break;
case ICM_20602_SPI:
gyroHardware = GYRO_ICM20602;
break;
case ICM_20608_SPI:
gyroHardware = GYRO_ICM20608G;
break;
default:
gyroHardware = GYRO_MPU6500;
}
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_SPI_MPU9250
case GYRO_MPU9250:
if (mpu9250SpiGyroDetect(dev)) {
gyroHardware = GYRO_MPU9250;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_SPI_ICM20649
case GYRO_ICM20649:
if (icm20649SpiGyroDetect(dev)) {
gyroHardware = GYRO_ICM20649;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_SPI_ICM20689
case GYRO_ICM20689:
if (icm20689SpiGyroDetect(dev)) {
gyroHardware = GYRO_ICM20689;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_SPI_ICM42605
case GYRO_ICM42605:
if (icm42605SpiGyroDetect(dev)) {
gyroHardware = GYRO_ICM42605;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_ACCGYRO_BMI160
case GYRO_BMI160:
if (bmi160SpiGyroDetect(dev)) {
gyroHardware = GYRO_BMI160;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_ACCGYRO_BMI270
case GYRO_BMI270:
if (bmi270SpiGyroDetect(dev)) {
gyroHardware = GYRO_BMI270;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_FAKE_GYRO
case GYRO_FAKE:
if (fakeGyroDetect(dev)) {
gyroHardware = GYRO_FAKE;
break;
}
FALLTHROUGH;
#endif
default:
gyroHardware = GYRO_NONE;
}
if (gyroHardware != GYRO_NONE) {
sensorsSet(SENSOR_GYRO);
}
return gyroHardware;
}
static void gyroPreInitSensor(const gyroDeviceConfig_t *config)
{
#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) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) \
|| defined(USE_GYRO_SPI_ICM20689) || defined(USE_ACCGYRO_BMI160) || defined(USE_ACCGYRO_BMI270)
mpuPreInit(config);
#else
UNUSED(config);
#endif
}
static bool gyroDetectSensor(gyroSensor_t *gyroSensor, const gyroDeviceConfig_t *config)
{
#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) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) \
|| defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_L3GD20) || defined(USE_ACCGYRO_BMI160) || defined(USE_ACCGYRO_BMI270)
bool gyroFound = mpuDetect(&gyroSensor->gyroDev, config);
#if !defined(USE_FAKE_GYRO) // Allow resorting to fake accgyro if defined
if (!gyroFound) {
return false;
}
#else
UNUSED(gyroFound);
#endif
#else
UNUSED(config);
#endif
const gyroHardware_e gyroHardware = gyroDetect(&gyroSensor->gyroDev);
gyroSensor->gyroDev.gyroHardware = gyroHardware;
return gyroHardware != GYRO_NONE;
}
static void gyroInitSensor(gyroSensor_t *gyroSensor, const gyroDeviceConfig_t *config)
{
gyroSensor->gyroDev.gyro_high_fsr = gyroConfig()->gyro_high_fsr;
gyroSensor->gyroDev.gyroAlign = config->alignment;
buildRotationMatrixFromAlignment(&config->customAlignment, &gyroSensor->gyroDev.rotationMatrix);
gyroSensor->gyroDev.mpuIntExtiTag = config->extiTag;
gyroSensor->gyroDev.hardware_lpf = gyroConfig()->gyro_hardware_lpf;
// The targetLooptime gets set later based on the active sensor's gyroSampleRateHz and pid_process_denom
gyroSensor->gyroDev.gyroSampleRateHz = gyroSetSampleRate(&gyroSensor->gyroDev);
gyroSensor->gyroDev.initFn(&gyroSensor->gyroDev);
// As new gyros are supported, be sure to add them below based on whether they are subject to the overflow/inversion bug
// Any gyro not explicitly defined will default to not having built-in overflow protection as a safe alternative.
switch (gyroSensor->gyroDev.gyroHardware) {
case GYRO_NONE: // Won't ever actually get here, but included to account for all gyro types
case GYRO_DEFAULT:
case GYRO_FAKE:
case GYRO_MPU6050:
case GYRO_L3G4200D:
case GYRO_MPU3050:
case GYRO_L3GD20:
case GYRO_BMI160:
case GYRO_BMI270:
case GYRO_MPU6000:
case GYRO_MPU6500:
case GYRO_MPU9250:
gyroSensor->gyroDev.gyroHasOverflowProtection = true;
break;
case GYRO_ICM20601:
case GYRO_ICM20602:
case GYRO_ICM20608G:
case GYRO_ICM20649: // we don't actually know if this is affected, but as there are currently no flight controllers using it we err on the side of caution
case GYRO_ICM20689:
gyroSensor->gyroDev.gyroHasOverflowProtection = false;
break;
default:
gyroSensor->gyroDev.gyroHasOverflowProtection = false; // default catch for newly added gyros until proven to be unaffected
break;
}
gyroInitSensorFilters(gyroSensor);
}
void gyroPreInit(void)
{
gyroPreInitSensor(gyroDeviceConfig(0));
#ifdef USE_MULTI_GYRO
gyroPreInitSensor(gyroDeviceConfig(1));
#endif
}
bool gyroInit(void)
{
#ifdef USE_GYRO_OVERFLOW_CHECK
if (gyroConfig()->checkOverflow == GYRO_OVERFLOW_CHECK_YAW) {
overflowAxisMask = GYRO_OVERFLOW_Z;
} else if (gyroConfig()->checkOverflow == GYRO_OVERFLOW_CHECK_ALL_AXES) {
overflowAxisMask = GYRO_OVERFLOW_X | GYRO_OVERFLOW_Y | GYRO_OVERFLOW_Z;
} else {
overflowAxisMask = 0;
}
#endif
gyroDebugMode = DEBUG_NONE;
useDualGyroDebugging = false;
switch (debugMode) {
case DEBUG_FFT:
case DEBUG_FFT_FREQ:
case DEBUG_GYRO_RAW:
case DEBUG_GYRO_SCALED:
case DEBUG_GYRO_FILTERED:
case DEBUG_DYN_LPF:
case DEBUG_GYRO_SAMPLE:
gyroDebugMode = debugMode;
break;
case DEBUG_DUAL_GYRO_DIFF:
case DEBUG_DUAL_GYRO_RAW:
case DEBUG_DUAL_GYRO_SCALED:
useDualGyroDebugging = true;
break;
}
firstArmingCalibrationWasStarted = false;
gyroDetectionFlags = NO_GYROS_DETECTED;
gyroToUse = gyroConfig()->gyro_to_use;
gyroDebugAxis = gyroConfig()->gyro_filter_debug_axis;
if (gyroDetectSensor(&gyroSensor1, gyroDeviceConfig(0))) {
gyroDetectionFlags |= DETECTED_GYRO_1;
}
#if defined(USE_MULTI_GYRO)
if (gyroDetectSensor(&gyroSensor2, gyroDeviceConfig(1))) {
gyroDetectionFlags |= DETECTED_GYRO_2;
}
#endif
if (gyroDetectionFlags == NO_GYROS_DETECTED) {
return false;
}
#if defined(USE_MULTI_GYRO)
if ((gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH && !((gyroDetectionFlags & DETECTED_BOTH_GYROS) == DETECTED_BOTH_GYROS))
|| (gyroToUse == GYRO_CONFIG_USE_GYRO_1 && !(gyroDetectionFlags & DETECTED_GYRO_1))
|| (gyroToUse == GYRO_CONFIG_USE_GYRO_2 && !(gyroDetectionFlags & DETECTED_GYRO_2))) {
if (gyroDetectionFlags & DETECTED_GYRO_1) {
gyroToUse = GYRO_CONFIG_USE_GYRO_1;
} else {
gyroToUse = GYRO_CONFIG_USE_GYRO_2;
}
gyroConfigMutable()->gyro_to_use = gyroToUse;
}
// Only allow using both gyros simultaneously if they are the same hardware type.
if (((gyroDetectionFlags & DETECTED_BOTH_GYROS) == DETECTED_BOTH_GYROS) && gyroSensor1.gyroDev.gyroHardware == gyroSensor2.gyroDev.gyroHardware) {
gyroDetectionFlags |= DETECTED_DUAL_GYROS;
} else if (gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
// If the user selected "BOTH" and they are not the same type, then reset to using only the first gyro.
gyroToUse = GYRO_CONFIG_USE_GYRO_1;
gyroConfigMutable()->gyro_to_use = gyroToUse;
}
if (gyroToUse == GYRO_CONFIG_USE_GYRO_2 || gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
gyroInitSensor(&gyroSensor2, gyroDeviceConfig(1));
gyroHasOverflowProtection = gyroHasOverflowProtection && gyroSensor2.gyroDev.gyroHasOverflowProtection;
detectedSensors[SENSOR_INDEX_GYRO] = gyroSensor2.gyroDev.gyroHardware;
}
#endif
if (gyroToUse == GYRO_CONFIG_USE_GYRO_1 || gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
gyroInitSensor(&gyroSensor1, gyroDeviceConfig(0));
gyroHasOverflowProtection = gyroHasOverflowProtection && gyroSensor1.gyroDev.gyroHasOverflowProtection;
detectedSensors[SENSOR_INDEX_GYRO] = gyroSensor1.gyroDev.gyroHardware;
}
// Copy the sensor's scale to the high-level gyro object. If running in "BOTH" mode
// then logic above requires both sensors to be the same so we'll use sensor1's scale.
// This will need to be revised if we ever allow different sensor types to be used simultaneously.
// Likewise determine the appropriate raw data for use in DEBUG_GYRO_RAW
gyro.scale = gyroSensor1.gyroDev.scale;
gyro.rawSensorDev = &gyroSensor1.gyroDev;
#if defined(USE_MULTI_GYRO)
if (gyroToUse == GYRO_CONFIG_USE_GYRO_2) {
gyro.scale = gyroSensor2.gyroDev.scale;
gyro.rawSensorDev = &gyroSensor2.gyroDev;
}
#endif
if (gyro.rawSensorDev) {
gyro.sampleRateHz = gyro.rawSensorDev->gyroSampleRateHz;
gyro.accSampleRateHz = gyro.rawSensorDev->accSampleRateHz;
} else {
gyro.sampleRateHz = 0;
gyro.accSampleRateHz = 0;
}
return true;
}
gyroDetectionFlags_t getGyroDetectionFlags(void)
{
return gyroDetectionFlags;
}
#ifdef USE_DYN_LPF
static FAST_RAM uint8_t dynLpfFilter = DYN_LPF_NONE;
static FAST_RAM_ZERO_INIT uint16_t dynLpfMin;
static FAST_RAM_ZERO_INIT uint16_t dynLpfMax;
static void dynLpfFilterInit()
{
if (gyroConfig()->dyn_lpf_gyro_min_hz > 0) {
switch (gyroConfig()->gyro_lowpass_type) {
case FILTER_PT1:
dynLpfFilter = DYN_LPF_PT1;
break;
case FILTER_BIQUAD:
dynLpfFilter = DYN_LPF_BIQUAD;
break;
default:
dynLpfFilter = DYN_LPF_NONE;
break;
}
} else {
dynLpfFilter = DYN_LPF_NONE;
}
dynLpfMin = gyroConfig()->dyn_lpf_gyro_min_hz;
dynLpfMax = gyroConfig()->dyn_lpf_gyro_max_hz;
}
#endif
bool gyroInitLowpassFilterLpf(int slot, int type, uint16_t lpfHz, uint32_t looptime)
{
filterApplyFnPtr *lowpassFilterApplyFn;
gyroLowpassFilter_t *lowpassFilter = NULL;
switch (slot) {
case FILTER_LOWPASS:
lowpassFilterApplyFn = &gyro.lowpassFilterApplyFn;
lowpassFilter = gyro.lowpassFilter;
break;
case FILTER_LOWPASS2:
lowpassFilterApplyFn = &gyro.lowpass2FilterApplyFn;
lowpassFilter = gyro.lowpass2Filter;
break;
default:
return false;
}
bool ret = false;
// Establish some common constants
const uint32_t gyroFrequencyNyquist = 1000000 / 2 / looptime;
const float gyroDt = looptime * 1e-6f;
// Gain could be calculated a little later as it is specific to the pt1/bqrcf2/fkf branches
const float gain = pt1FilterGain(lpfHz, gyroDt);
// Dereference the pointer to null before checking valid cutoff and filter
// type. It will be overridden for positive cases.
*lowpassFilterApplyFn = nullFilterApply;
// If lowpass cutoff has been specified and is less than the Nyquist frequency
if (lpfHz && lpfHz <= gyroFrequencyNyquist) {
switch (type) {
case FILTER_PT1:
*lowpassFilterApplyFn = (filterApplyFnPtr) pt1FilterApply;
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
pt1FilterInit(&lowpassFilter[axis].pt1FilterState, gain);
}
ret = true;
break;
case FILTER_BIQUAD:
#ifdef USE_DYN_LPF
*lowpassFilterApplyFn = (filterApplyFnPtr) biquadFilterApplyDF1;
#else
*lowpassFilterApplyFn = (filterApplyFnPtr) biquadFilterApply;
#endif
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
biquadFilterInitLPF(&lowpassFilter[axis].biquadFilterState, lpfHz, looptime);
}
ret = true;
break;
}
}
return ret;
}
static uint16_t calculateNyquistAdjustedNotchHz(uint16_t notchHz, uint16_t notchCutoffHz)
{
const uint32_t gyroFrequencyNyquist = 1000000 / 2 / gyro.targetLooptime;
if (notchHz > gyroFrequencyNyquist) {
if (notchCutoffHz < gyroFrequencyNyquist) {
notchHz = gyroFrequencyNyquist;
} else {
notchHz = 0;
}
}
return notchHz;
}
#if defined(USE_GYRO_SLEW_LIMITER)
void gyroInitSlewLimiter(gyroSensor_t *gyroSensor) {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
gyroSensor->gyroDev.gyroADCRawPrevious[axis] = 0;
}
}
#endif
static void gyroInitFilterNotch1(uint16_t notchHz, uint16_t notchCutoffHz)
{
gyro.notchFilter1ApplyFn = nullFilterApply;
notchHz = calculateNyquistAdjustedNotchHz(notchHz, notchCutoffHz);
if (notchHz != 0 && notchCutoffHz != 0) {
gyro.notchFilter1ApplyFn = (filterApplyFnPtr)biquadFilterApply;
const float notchQ = filterGetNotchQ(notchHz, notchCutoffHz);
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
biquadFilterInit(&gyro.notchFilter1[axis], notchHz, gyro.targetLooptime, notchQ, FILTER_NOTCH);
}
}
}
static void gyroInitFilterNotch2(uint16_t notchHz, uint16_t notchCutoffHz)
{
gyro.notchFilter2ApplyFn = nullFilterApply;
notchHz = calculateNyquistAdjustedNotchHz(notchHz, notchCutoffHz);
if (notchHz != 0 && notchCutoffHz != 0) {
gyro.notchFilter2ApplyFn = (filterApplyFnPtr)biquadFilterApply;
const float notchQ = filterGetNotchQ(notchHz, notchCutoffHz);
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
biquadFilterInit(&gyro.notchFilter2[axis], notchHz, gyro.targetLooptime, notchQ, FILTER_NOTCH);
}
}
}
#ifdef USE_GYRO_DATA_ANALYSE
static bool isDynamicFilterActive(void)
bool isDynamicFilterActive(void)
{
return featureIsEnabled(FEATURE_DYNAMIC_FILTER);
}
static void gyroInitFilterDynamicNotch()
{
gyro.notchFilterDynApplyFn = nullFilterApply;
gyro.notchFilterDynApplyFn2 = nullFilterApply;
if (isDynamicFilterActive()) {
gyro.notchFilterDynApplyFn = (filterApplyFnPtr)biquadFilterApplyDF1; // must be this function, not DF2
if(gyroConfig()->dyn_notch_width_percent != 0) {
gyro.notchFilterDynApplyFn2 = (filterApplyFnPtr)biquadFilterApplyDF1; // must be this function, not DF2
}
const float notchQ = filterGetNotchQ(DYNAMIC_NOTCH_DEFAULT_CENTER_HZ, DYNAMIC_NOTCH_DEFAULT_CUTOFF_HZ); // any defaults OK here
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
biquadFilterInit(&gyro.notchFilterDyn[axis], DYNAMIC_NOTCH_DEFAULT_CENTER_HZ, gyro.targetLooptime, notchQ, FILTER_NOTCH);
biquadFilterInit(&gyro.notchFilterDyn2[axis], DYNAMIC_NOTCH_DEFAULT_CENTER_HZ, gyro.targetLooptime, notchQ, FILTER_NOTCH);
}
}
}
#endif
static void gyroInitSensorFilters(gyroSensor_t *gyroSensor)
{
#if defined(USE_GYRO_SLEW_LIMITER)
gyroInitSlewLimiter(gyroSensor);
#else
UNUSED(gyroSensor);
#endif
}
void gyroSetTargetLooptime(uint8_t pidDenom)
{
activePidLoopDenom = pidDenom;
if (gyro.sampleRateHz) {
gyro.sampleLooptime = 1e6 / gyro.sampleRateHz;
gyro.targetLooptime = activePidLoopDenom * 1e6 / gyro.sampleRateHz;
} else {
gyro.sampleLooptime = 0;
gyro.targetLooptime = 0;
}
}
void gyroInitFilters(void)
{
uint16_t gyro_lowpass_hz = gyroConfig()->gyro_lowpass_hz;
#ifdef USE_DYN_LPF
if (gyroConfig()->dyn_lpf_gyro_min_hz > 0) {
gyro_lowpass_hz = gyroConfig()->dyn_lpf_gyro_min_hz;
}
#endif
gyroInitLowpassFilterLpf(
FILTER_LOWPASS,
gyroConfig()->gyro_lowpass_type,
gyro_lowpass_hz,
gyro.targetLooptime
);
gyro.downsampleFilterEnabled = gyroInitLowpassFilterLpf(
FILTER_LOWPASS2,
gyroConfig()->gyro_lowpass2_type,
gyroConfig()->gyro_lowpass2_hz,
gyro.sampleLooptime
);
gyroInitFilterNotch1(gyroConfig()->gyro_soft_notch_hz_1, gyroConfig()->gyro_soft_notch_cutoff_1);
gyroInitFilterNotch2(gyroConfig()->gyro_soft_notch_hz_2, gyroConfig()->gyro_soft_notch_cutoff_2);
#ifdef USE_GYRO_DATA_ANALYSE
gyroInitFilterDynamicNotch();
#endif
#ifdef USE_DYN_LPF
dynLpfFilterInit();
#endif
#ifdef USE_GYRO_DATA_ANALYSE
gyroDataAnalyseStateInit(&gyro.gyroAnalyseState, gyro.targetLooptime);
#endif
}
FAST_CODE bool isGyroSensorCalibrationComplete(const gyroSensor_t *gyroSensor)
{
return gyroSensor->calibration.cyclesRemaining == 0;
@ -819,17 +148,17 @@ FAST_CODE bool isGyroSensorCalibrationComplete(const gyroSensor_t *gyroSensor)
FAST_CODE bool gyroIsCalibrationComplete(void)
{
switch (gyroToUse) {
switch (gyro.gyroToUse) {
default:
case GYRO_CONFIG_USE_GYRO_1: {
return isGyroSensorCalibrationComplete(&gyroSensor1);
return isGyroSensorCalibrationComplete(&gyro.gyroSensor1);
}
#ifdef USE_MULTI_GYRO
case GYRO_CONFIG_USE_GYRO_2: {
return isGyroSensorCalibrationComplete(&gyroSensor2);
return isGyroSensorCalibrationComplete(&gyro.gyroSensor2);
}
case GYRO_CONFIG_USE_GYRO_BOTH: {
return isGyroSensorCalibrationComplete(&gyroSensor1) && isGyroSensorCalibrationComplete(&gyroSensor2);
return isGyroSensorCalibrationComplete(&gyro.gyroSensor1) && isGyroSensorCalibrationComplete(&gyro.gyroSensor2);
}
#endif
}
@ -867,9 +196,9 @@ void gyroStartCalibration(bool isFirstArmingCalibration)
return;
}
gyroSetCalibrationCycles(&gyroSensor1);
gyroSetCalibrationCycles(&gyro.gyroSensor1);
#ifdef USE_MULTI_GYRO
gyroSetCalibrationCycles(&gyroSensor2);
gyroSetCalibrationCycles(&gyro.gyroSensor2);
#endif
if (isFirstArmingCalibration) {
@ -933,7 +262,7 @@ STATIC_UNIT_TESTED void performGyroCalibration(gyroSensor_t *gyroSensor, uint8_t
FAST_CODE int32_t gyroSlewLimiter(gyroSensor_t *gyroSensor, int axis)
{
int32_t ret = (int32_t)gyroSensor->gyroDev.gyroADCRaw[axis];
if (gyroConfig()->checkOverflow || gyroHasOverflowProtection) {
if (gyroConfig()->checkOverflow || gyro.gyroHasOverflowProtection) {
// don't use the slew limiter if overflow checking is on or gyro is not subject to overflow bug
return ret;
}
@ -998,7 +327,7 @@ static FAST_CODE void checkForOverflow(timeUs_t currentTimeUs)
if (fabsf(gyro.gyroADCf[Z]) > gyroOverflowTriggerRate) {
overflowCheck |= GYRO_OVERFLOW_Z;
}
if (overflowCheck & overflowAxisMask) {
if (overflowCheck & gyro.overflowAxisMask) {
overflowDetected = true;
overflowTimeUs = currentTimeUs;
#ifdef USE_YAW_SPIN_RECOVERY
@ -1081,31 +410,31 @@ static FAST_CODE FAST_CODE_NOINLINE void gyroUpdateSensor(gyroSensor_t *gyroSens
FAST_CODE void gyroUpdate(void)
{
switch (gyroToUse) {
switch (gyro.gyroToUse) {
case GYRO_CONFIG_USE_GYRO_1:
gyroUpdateSensor(&gyroSensor1);
if (isGyroSensorCalibrationComplete(&gyroSensor1)) {
gyro.gyroADC[X] = gyroSensor1.gyroDev.gyroADC[X] * gyroSensor1.gyroDev.scale;
gyro.gyroADC[Y] = gyroSensor1.gyroDev.gyroADC[Y] * gyroSensor1.gyroDev.scale;
gyro.gyroADC[Z] = gyroSensor1.gyroDev.gyroADC[Z] * gyroSensor1.gyroDev.scale;
gyroUpdateSensor(&gyro.gyroSensor1);
if (isGyroSensorCalibrationComplete(&gyro.gyroSensor1)) {
gyro.gyroADC[X] = gyro.gyroSensor1.gyroDev.gyroADC[X] * gyro.gyroSensor1.gyroDev.scale;
gyro.gyroADC[Y] = gyro.gyroSensor1.gyroDev.gyroADC[Y] * gyro.gyroSensor1.gyroDev.scale;
gyro.gyroADC[Z] = gyro.gyroSensor1.gyroDev.gyroADC[Z] * gyro.gyroSensor1.gyroDev.scale;
}
break;
#ifdef USE_MULTI_GYRO
case GYRO_CONFIG_USE_GYRO_2:
gyroUpdateSensor(&gyroSensor2);
if (isGyroSensorCalibrationComplete(&gyroSensor2)) {
gyro.gyroADC[X] = gyroSensor2.gyroDev.gyroADC[X] * gyroSensor2.gyroDev.scale;
gyro.gyroADC[Y] = gyroSensor2.gyroDev.gyroADC[Y] * gyroSensor2.gyroDev.scale;
gyro.gyroADC[Z] = gyroSensor2.gyroDev.gyroADC[Z] * gyroSensor2.gyroDev.scale;
gyroUpdateSensor(&gyro.gyroSensor2);
if (isGyroSensorCalibrationComplete(&gyro.gyroSensor2)) {
gyro.gyroADC[X] = gyro.gyroSensor2.gyroDev.gyroADC[X] * gyro.gyroSensor2.gyroDev.scale;
gyro.gyroADC[Y] = gyro.gyroSensor2.gyroDev.gyroADC[Y] * gyro.gyroSensor2.gyroDev.scale;
gyro.gyroADC[Z] = gyro.gyroSensor2.gyroDev.gyroADC[Z] * gyro.gyroSensor2.gyroDev.scale;
}
break;
case GYRO_CONFIG_USE_GYRO_BOTH:
gyroUpdateSensor(&gyroSensor1);
gyroUpdateSensor(&gyroSensor2);
if (isGyroSensorCalibrationComplete(&gyroSensor1) && isGyroSensorCalibrationComplete(&gyroSensor2)) {
gyro.gyroADC[X] = ((gyroSensor1.gyroDev.gyroADC[X] * gyroSensor1.gyroDev.scale) + (gyroSensor2.gyroDev.gyroADC[X] * gyroSensor2.gyroDev.scale)) / 2.0f;
gyro.gyroADC[Y] = ((gyroSensor1.gyroDev.gyroADC[Y] * gyroSensor1.gyroDev.scale) + (gyroSensor2.gyroDev.gyroADC[Y] * gyroSensor2.gyroDev.scale)) / 2.0f;
gyro.gyroADC[Z] = ((gyroSensor1.gyroDev.gyroADC[Z] * gyroSensor1.gyroDev.scale) + (gyroSensor2.gyroDev.gyroADC[Z] * gyroSensor2.gyroDev.scale)) / 2.0f;
gyroUpdateSensor(&gyro.gyroSensor1);
gyroUpdateSensor(&gyro.gyroSensor2);
if (isGyroSensorCalibrationComplete(&gyro.gyroSensor1) && isGyroSensorCalibrationComplete(&gyro.gyroSensor2)) {
gyro.gyroADC[X] = ((gyro.gyroSensor1.gyroDev.gyroADC[X] * gyro.gyroSensor1.gyroDev.scale) + (gyro.gyroSensor2.gyroDev.gyroADC[X] * gyro.gyroSensor2.gyroDev.scale)) / 2.0f;
gyro.gyroADC[Y] = ((gyro.gyroSensor1.gyroDev.gyroADC[Y] * gyro.gyroSensor1.gyroDev.scale) + (gyro.gyroSensor2.gyroDev.gyroADC[Y] * gyro.gyroSensor2.gyroDev.scale)) / 2.0f;
gyro.gyroADC[Z] = ((gyro.gyroSensor1.gyroDev.gyroADC[Z] * gyro.gyroSensor1.gyroDev.scale) + (gyro.gyroSensor2.gyroDev.gyroADC[Z] * gyro.gyroSensor2.gyroDev.scale)) / 2.0f;
}
break;
#endif
@ -1135,7 +464,7 @@ FAST_CODE void gyroUpdate(void)
#define GYRO_FILTER_FUNCTION_NAME filterGyroDebug
#define GYRO_FILTER_DEBUG_SET DEBUG_SET
#define GYRO_FILTER_AXIS_DEBUG_SET(axis, mode, index, value) if (axis == (int)gyroDebugAxis) DEBUG_SET(mode, index, value)
#define GYRO_FILTER_AXIS_DEBUG_SET(axis, mode, index, value) if (axis == (int)gyro.gyroDebugAxis) DEBUG_SET(mode, index, value)
#include "gyro_filter_impl.c"
#undef GYRO_FILTER_FUNCTION_NAME
#undef GYRO_FILTER_DEBUG_SET
@ -1143,7 +472,7 @@ FAST_CODE void gyroUpdate(void)
FAST_CODE void gyroFiltering(timeUs_t currentTimeUs)
{
if (gyroDebugMode == DEBUG_NONE) {
if (gyro.gyroDebugMode == DEBUG_NONE) {
filterGyro();
} else {
filterGyroDebug();
@ -1155,42 +484,42 @@ FAST_CODE void gyroFiltering(timeUs_t currentTimeUs)
}
#endif
if (useDualGyroDebugging) {
switch (gyroToUse) {
if (gyro.useDualGyroDebugging) {
switch (gyro.gyroToUse) {
case GYRO_CONFIG_USE_GYRO_1:
DEBUG_SET(DEBUG_DUAL_GYRO_RAW, 0, gyroSensor1.gyroDev.gyroADCRaw[X]);
DEBUG_SET(DEBUG_DUAL_GYRO_RAW, 1, gyroSensor1.gyroDev.gyroADCRaw[Y]);
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 0, lrintf(gyroSensor1.gyroDev.gyroADC[X] * gyroSensor1.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 1, lrintf(gyroSensor1.gyroDev.gyroADC[Y] * gyroSensor1.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_RAW, 0, gyro.gyroSensor1.gyroDev.gyroADCRaw[X]);
DEBUG_SET(DEBUG_DUAL_GYRO_RAW, 1, gyro.gyroSensor1.gyroDev.gyroADCRaw[Y]);
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 0, lrintf(gyro.gyroSensor1.gyroDev.gyroADC[X] * gyro.gyroSensor1.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 1, lrintf(gyro.gyroSensor1.gyroDev.gyroADC[Y] * gyro.gyroSensor1.gyroDev.scale));
break;
#ifdef USE_MULTI_GYRO
case GYRO_CONFIG_USE_GYRO_2:
DEBUG_SET(DEBUG_DUAL_GYRO_RAW, 2, gyroSensor2.gyroDev.gyroADCRaw[X]);
DEBUG_SET(DEBUG_DUAL_GYRO_RAW, 3, gyroSensor2.gyroDev.gyroADCRaw[Y]);
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 2, lrintf(gyroSensor2.gyroDev.gyroADC[X] * gyroSensor2.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 3, lrintf(gyroSensor2.gyroDev.gyroADC[Y] * gyroSensor2.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_RAW, 2, gyro.gyroSensor2.gyroDev.gyroADCRaw[X]);
DEBUG_SET(DEBUG_DUAL_GYRO_RAW, 3, gyro.gyroSensor2.gyroDev.gyroADCRaw[Y]);
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 2, lrintf(gyro.gyroSensor2.gyroDev.gyroADC[X] * gyro.gyroSensor2.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 3, lrintf(gyro.gyroSensor2.gyroDev.gyroADC[Y] * gyro.gyroSensor2.gyroDev.scale));
break;
case GYRO_CONFIG_USE_GYRO_BOTH:
DEBUG_SET(DEBUG_DUAL_GYRO_RAW, 0, gyroSensor1.gyroDev.gyroADCRaw[X]);
DEBUG_SET(DEBUG_DUAL_GYRO_RAW, 1, gyroSensor1.gyroDev.gyroADCRaw[Y]);
DEBUG_SET(DEBUG_DUAL_GYRO_RAW, 2, gyroSensor2.gyroDev.gyroADCRaw[X]);
DEBUG_SET(DEBUG_DUAL_GYRO_RAW, 3, gyroSensor2.gyroDev.gyroADCRaw[Y]);
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 0, lrintf(gyroSensor1.gyroDev.gyroADC[X] * gyroSensor1.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 1, lrintf(gyroSensor1.gyroDev.gyroADC[Y] * gyroSensor1.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 2, lrintf(gyroSensor2.gyroDev.gyroADC[X] * gyroSensor2.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 3, lrintf(gyroSensor2.gyroDev.gyroADC[Y] * gyroSensor2.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_DIFF, 0, lrintf((gyroSensor1.gyroDev.gyroADC[X] * gyroSensor1.gyroDev.scale) - (gyroSensor2.gyroDev.gyroADC[X] * gyroSensor2.gyroDev.scale)));
DEBUG_SET(DEBUG_DUAL_GYRO_DIFF, 1, lrintf((gyroSensor1.gyroDev.gyroADC[Y] * gyroSensor1.gyroDev.scale) - (gyroSensor2.gyroDev.gyroADC[Y] * gyroSensor2.gyroDev.scale)));
DEBUG_SET(DEBUG_DUAL_GYRO_DIFF, 2, lrintf((gyroSensor1.gyroDev.gyroADC[Z] * gyroSensor1.gyroDev.scale) - (gyroSensor2.gyroDev.gyroADC[Z] * gyroSensor2.gyroDev.scale)));
DEBUG_SET(DEBUG_DUAL_GYRO_RAW, 0, gyro.gyroSensor1.gyroDev.gyroADCRaw[X]);
DEBUG_SET(DEBUG_DUAL_GYRO_RAW, 1, gyro.gyroSensor1.gyroDev.gyroADCRaw[Y]);
DEBUG_SET(DEBUG_DUAL_GYRO_RAW, 2, gyro.gyroSensor2.gyroDev.gyroADCRaw[X]);
DEBUG_SET(DEBUG_DUAL_GYRO_RAW, 3, gyro.gyroSensor2.gyroDev.gyroADCRaw[Y]);
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 0, lrintf(gyro.gyroSensor1.gyroDev.gyroADC[X] * gyro.gyroSensor1.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 1, lrintf(gyro.gyroSensor1.gyroDev.gyroADC[Y] * gyro.gyroSensor1.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 2, lrintf(gyro.gyroSensor2.gyroDev.gyroADC[X] * gyro.gyroSensor2.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_SCALED, 3, lrintf(gyro.gyroSensor2.gyroDev.gyroADC[Y] * gyro.gyroSensor2.gyroDev.scale));
DEBUG_SET(DEBUG_DUAL_GYRO_DIFF, 0, lrintf((gyro.gyroSensor1.gyroDev.gyroADC[X] * gyro.gyroSensor1.gyroDev.scale) - (gyro.gyroSensor2.gyroDev.gyroADC[X] * gyro.gyroSensor2.gyroDev.scale)));
DEBUG_SET(DEBUG_DUAL_GYRO_DIFF, 1, lrintf((gyro.gyroSensor1.gyroDev.gyroADC[Y] * gyro.gyroSensor1.gyroDev.scale) - (gyro.gyroSensor2.gyroDev.gyroADC[Y] * gyro.gyroSensor2.gyroDev.scale)));
DEBUG_SET(DEBUG_DUAL_GYRO_DIFF, 2, lrintf((gyro.gyroSensor1.gyroDev.gyroADC[Z] * gyro.gyroSensor1.gyroDev.scale) - (gyro.gyroSensor2.gyroDev.gyroADC[Z] * gyro.gyroSensor2.gyroDev.scale)));
break;
#endif
}
}
#ifdef USE_GYRO_OVERFLOW_CHECK
if (gyroConfig()->checkOverflow && !gyroHasOverflowProtection) {
if (gyroConfig()->checkOverflow && !gyro.gyroHasOverflowProtection) {
checkForOverflow(currentTimeUs);
}
#endif
@ -1244,18 +573,18 @@ int16_t gyroReadSensorTemperature(gyroSensor_t gyroSensor)
void gyroReadTemperature(void)
{
switch (gyroToUse) {
switch (gyro.gyroToUse) {
case GYRO_CONFIG_USE_GYRO_1:
gyroSensorTemperature = gyroReadSensorTemperature(gyroSensor1);
gyroSensorTemperature = gyroReadSensorTemperature(gyro.gyroSensor1);
break;
#ifdef USE_MULTI_GYRO
case GYRO_CONFIG_USE_GYRO_2:
gyroSensorTemperature = gyroReadSensorTemperature(gyroSensor2);
gyroSensorTemperature = gyroReadSensorTemperature(gyro.gyroSensor2);
break;
case GYRO_CONFIG_USE_GYRO_BOTH:
gyroSensorTemperature = MAX(gyroReadSensorTemperature(gyroSensor1), gyroReadSensorTemperature(gyroSensor2));
gyroSensorTemperature = MAX(gyroReadSensorTemperature(gyro.gyroSensor1), gyroReadSensorTemperature(gyro.gyroSensor2));
break;
#endif // USE_MULTI_GYRO
}
@ -1266,11 +595,6 @@ int16_t gyroGetTemperature(void)
return gyroSensorTemperature;
}
int16_t gyroRateDps(int axis)
{
return lrintf(gyro.gyroADCf[axis] / ACTIVE_GYRO->gyroDev.scale);
}
bool gyroOverflowDetected(void)
{
#ifdef USE_GYRO_OVERFLOW_CHECK
@ -1292,13 +616,6 @@ uint16_t gyroAbsRateDps(int axis)
return fabsf(gyro.gyroADCf[axis]);
}
#ifdef USE_GYRO_REGISTER_DUMP
uint8_t gyroReadRegister(uint8_t whichSensor, uint8_t reg)
{
return mpuGyroReadRegister(gyroSensorBusByDevice(whichSensor), reg);
}
#endif // USE_GYRO_REGISTER_DUMP
#ifdef USE_DYN_LPF
float dynThrottle(float throttle) {
@ -1307,16 +624,16 @@ float dynThrottle(float throttle) {
void dynLpfGyroUpdate(float throttle)
{
if (dynLpfFilter != DYN_LPF_NONE) {
const unsigned int cutoffFreq = fmax(dynThrottle(throttle) * dynLpfMax, dynLpfMin);
if (gyro.dynLpfFilter != DYN_LPF_NONE) {
const unsigned int cutoffFreq = fmax(dynThrottle(throttle) * gyro.dynLpfMax, gyro.dynLpfMin);
if (dynLpfFilter == DYN_LPF_PT1) {
if (gyro.dynLpfFilter == DYN_LPF_PT1) {
DEBUG_SET(DEBUG_DYN_LPF, 2, cutoffFreq);
const float gyroDt = gyro.targetLooptime * 1e-6f;
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
pt1FilterUpdateCutoff(&gyro.lowpassFilter[axis].pt1FilterState, pt1FilterGain(cutoffFreq, gyroDt));
}
} else if (dynLpfFilter == DYN_LPF_BIQUAD) {
} else if (gyro.dynLpfFilter == DYN_LPF_BIQUAD) {
DEBUG_SET(DEBUG_DYN_LPF, 2, cutoffFreq);
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
biquadFilterUpdateLPF(&gyro.lowpassFilter[axis].biquadFilterState, cutoffFreq, gyro.targetLooptime);

View File

@ -48,6 +48,27 @@ typedef union gyroLowpassFilter_u {
biquadFilter_t biquadFilterState;
} gyroLowpassFilter_t;
typedef enum gyroDetectionFlags_e {
NO_GYROS_DETECTED = 0,
DETECTED_GYRO_1 = (1 << 0),
#if defined(USE_MULTI_GYRO)
DETECTED_GYRO_2 = (1 << 1),
DETECTED_BOTH_GYROS = (DETECTED_GYRO_1 | DETECTED_GYRO_2),
DETECTED_DUAL_GYROS = (1 << 7), // All gyros are of the same hardware type
#endif
} gyroDetectionFlags_t;
typedef struct gyroCalibration_s {
float sum[XYZ_AXIS_COUNT];
stdev_t var[XYZ_AXIS_COUNT];
int32_t cyclesRemaining;
} gyroCalibration_t;
typedef struct gyroSensor_s {
gyroDev_t gyroDev;
gyroCalibration_t calibration;
} gyroSensor_t;
typedef struct gyro_s {
uint16_t sampleRateHz;
uint32_t targetLooptime;
@ -59,6 +80,11 @@ typedef struct gyro_s {
float sampleSum[XYZ_AXIS_COUNT]; // summed samples used for downsampling
bool downsampleFilterEnabled; // if true then downsample using gyro lowpass 2, otherwise use averaging
gyroSensor_t gyroSensor1;
#ifdef USE_MULTI_GYRO
gyroSensor_t gyroSensor2;
#endif
gyroDev_t *rawSensorDev; // pointer to the sensor providing the raw data for DEBUG_GYRO_RAW
// lowpass gyro soft filter
@ -86,6 +112,22 @@ typedef struct gyro_s {
#endif
uint16_t accSampleRateHz;
uint8_t gyroToUse;
uint8_t gyroDebugMode;
bool gyroHasOverflowProtection;
bool useDualGyroDebugging;
flight_dynamics_index_t gyroDebugAxis;
#ifdef USE_DYN_LPF
uint8_t dynLpfFilter;
uint16_t dynLpfMin;
uint16_t dynLpfMax;
#endif
#ifdef USE_GYRO_OVERFLOW_CHECK
uint8_t overflowAxisMask;
#endif
} gyro_t;
extern gyro_t gyro;
@ -118,16 +160,6 @@ enum {
FILTER_LOWPASS2
};
typedef enum gyroDetectionFlags_e {
NO_GYROS_DETECTED = 0,
DETECTED_GYRO_1 = (1 << 0),
#if defined(USE_MULTI_GYRO)
DETECTED_GYRO_2 = (1 << 1),
DETECTED_BOTH_GYROS = (DETECTED_GYRO_1 | DETECTED_GYRO_2),
DETECTED_DUAL_GYROS = (1 << 7), // All gyros are of the same hardware type
#endif
} gyroDetectionFlags_t;
typedef struct gyroConfig_s {
uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default.
uint8_t gyro_hardware_lpf; // gyro DLPF setting
@ -167,27 +199,17 @@ typedef struct gyroConfig_s {
PG_DECLARE(gyroConfig_t, gyroConfig);
void gyroPreInit(void);
bool gyroInit(void);
void gyroSetTargetLooptime(uint8_t pidDenom);
void gyroInitFilters(void);
void gyroUpdate(void);
void gyroFiltering(timeUs_t currentTimeUs);
bool gyroGetAccumulationAverage(float *accumulation);
const busDevice_t *gyroSensorBus(void);
struct mpuDetectionResult_s;
const struct mpuDetectionResult_s *gyroMpuDetectionResult(void);
void gyroStartCalibration(bool isFirstArmingCalibration);
bool isFirstArmingGyroCalibrationRunning(void);
bool gyroIsCalibrationComplete(void);
void gyroReadTemperature(void);
int16_t gyroGetTemperature(void);
int16_t gyroRateDps(int axis);
bool gyroOverflowDetected(void);
bool gyroYawSpinDetected(void);
uint16_t gyroAbsRateDps(int axis);
uint8_t gyroReadRegister(uint8_t whichSensor, uint8_t reg);
gyroDetectionFlags_t getGyroDetectionFlags(void);
#ifdef USE_DYN_LPF
float dynThrottle(float throttle);
void dynLpfGyroUpdate(float throttle);
@ -195,3 +217,6 @@ void dynLpfGyroUpdate(float throttle);
#ifdef USE_YAW_SPIN_RECOVERY
void initYawSpinRecovery(int maxYawRate);
#endif
#ifdef USE_GYRO_DATA_ANALYSE
bool isDynamicFilterActive(void);
#endif

View File

@ -51,7 +51,7 @@ static FAST_CODE void GYRO_FILTER_FUNCTION_NAME(void)
#ifdef USE_GYRO_DATA_ANALYSE
if (isDynamicFilterActive()) {
if (axis == gyroDebugAxis) {
if (axis == gyro.gyroDebugAxis) {
GYRO_FILTER_DEBUG_SET(DEBUG_FFT, 0, lrintf(gyroADCf));
GYRO_FILTER_DEBUG_SET(DEBUG_FFT_FREQ, 3, lrintf(gyroADCf));
GYRO_FILTER_DEBUG_SET(DEBUG_DYN_LPF, 0, lrintf(gyroADCf));
@ -76,7 +76,7 @@ static FAST_CODE void GYRO_FILTER_FUNCTION_NAME(void)
#ifdef USE_GYRO_DATA_ANALYSE
if (isDynamicFilterActive()) {
if (axis == gyroDebugAxis) {
if (axis == gyro.gyroDebugAxis) {
GYRO_FILTER_DEBUG_SET(DEBUG_FFT, 1, lrintf(gyroADCf));
GYRO_FILTER_DEBUG_SET(DEBUG_FFT_FREQ, 2, lrintf(gyroADCf));
GYRO_FILTER_DEBUG_SET(DEBUG_DYN_LPF, 3, lrintf(gyroADCf));

View File

@ -0,0 +1,695 @@
/*
* 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)
* any later version.
*
* 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.
* 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.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <math.h>
#include <stdlib.h>
#include "platform.h"
#include "build/debug.h"
#include "common/axis.h"
#include "common/maths.h"
#include "common/filter.h"
#include "drivers/accgyro/accgyro.h"
#include "drivers/accgyro/accgyro_fake.h"
#include "drivers/accgyro/accgyro_mpu.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"
#include "drivers/accgyro/accgyro_spi_icm20649.h"
#include "drivers/accgyro/accgyro_spi_icm20689.h"
#include "drivers/accgyro/accgyro_spi_icm20689.h"
#include "drivers/accgyro/accgyro_spi_icm42605.h"
#include "drivers/accgyro/accgyro_spi_mpu6000.h"
#include "drivers/accgyro/accgyro_spi_mpu6500.h"
#include "drivers/accgyro/accgyro_spi_mpu9250.h"
#ifdef USE_GYRO_L3GD20
#include "drivers/accgyro/accgyro_spi_l3gd20.h"
#endif
#ifdef USE_GYRO_L3G4200D
#include "drivers/accgyro_legacy/accgyro_l3g4200d.h"
#endif
#include "drivers/accgyro/gyro_sync.h"
#include "fc/runtime_config.h"
#ifdef USE_GYRO_DATA_ANALYSE
#include "flight/gyroanalyse.h"
#endif
#include "pg/gyrodev.h"
#include "sensors/gyro.h"
#include "sensors/sensors.h"
#ifdef USE_GYRO_DATA_ANALYSE
#define DYNAMIC_NOTCH_DEFAULT_CENTER_HZ 350
#define DYNAMIC_NOTCH_DEFAULT_CUTOFF_HZ 300
#endif
#ifdef USE_MULTI_GYRO
#define ACTIVE_GYRO ((gyro.gyroToUse == GYRO_CONFIG_USE_GYRO_2) ? &gyro.gyroSensor2 : &gyro.gyroSensor1)
#else
#define ACTIVE_GYRO (&gyro.gyroSensor1)
#endif
static gyroDetectionFlags_t gyroDetectionFlags = NO_GYROS_DETECTED;
static uint16_t calculateNyquistAdjustedNotchHz(uint16_t notchHz, uint16_t notchCutoffHz)
{
const uint32_t gyroFrequencyNyquist = 1000000 / 2 / gyro.targetLooptime;
if (notchHz > gyroFrequencyNyquist) {
if (notchCutoffHz < gyroFrequencyNyquist) {
notchHz = gyroFrequencyNyquist;
} else {
notchHz = 0;
}
}
return notchHz;
}
static void gyroInitFilterNotch1(uint16_t notchHz, uint16_t notchCutoffHz)
{
gyro.notchFilter1ApplyFn = nullFilterApply;
notchHz = calculateNyquistAdjustedNotchHz(notchHz, notchCutoffHz);
if (notchHz != 0 && notchCutoffHz != 0) {
gyro.notchFilter1ApplyFn = (filterApplyFnPtr)biquadFilterApply;
const float notchQ = filterGetNotchQ(notchHz, notchCutoffHz);
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
biquadFilterInit(&gyro.notchFilter1[axis], notchHz, gyro.targetLooptime, notchQ, FILTER_NOTCH);
}
}
}
static void gyroInitFilterNotch2(uint16_t notchHz, uint16_t notchCutoffHz)
{
gyro.notchFilter2ApplyFn = nullFilterApply;
notchHz = calculateNyquistAdjustedNotchHz(notchHz, notchCutoffHz);
if (notchHz != 0 && notchCutoffHz != 0) {
gyro.notchFilter2ApplyFn = (filterApplyFnPtr)biquadFilterApply;
const float notchQ = filterGetNotchQ(notchHz, notchCutoffHz);
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
biquadFilterInit(&gyro.notchFilter2[axis], notchHz, gyro.targetLooptime, notchQ, FILTER_NOTCH);
}
}
}
#ifdef USE_GYRO_DATA_ANALYSE
static void gyroInitFilterDynamicNotch()
{
gyro.notchFilterDynApplyFn = nullFilterApply;
gyro.notchFilterDynApplyFn2 = nullFilterApply;
if (isDynamicFilterActive()) {
gyro.notchFilterDynApplyFn = (filterApplyFnPtr)biquadFilterApplyDF1; // must be this function, not DF2
if(gyroConfig()->dyn_notch_width_percent != 0) {
gyro.notchFilterDynApplyFn2 = (filterApplyFnPtr)biquadFilterApplyDF1; // must be this function, not DF2
}
const float notchQ = filterGetNotchQ(DYNAMIC_NOTCH_DEFAULT_CENTER_HZ, DYNAMIC_NOTCH_DEFAULT_CUTOFF_HZ); // any defaults OK here
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
biquadFilterInit(&gyro.notchFilterDyn[axis], DYNAMIC_NOTCH_DEFAULT_CENTER_HZ, gyro.targetLooptime, notchQ, FILTER_NOTCH);
biquadFilterInit(&gyro.notchFilterDyn2[axis], DYNAMIC_NOTCH_DEFAULT_CENTER_HZ, gyro.targetLooptime, notchQ, FILTER_NOTCH);
}
}
}
#endif
static bool gyroInitLowpassFilterLpf(int slot, int type, uint16_t lpfHz, uint32_t looptime)
{
filterApplyFnPtr *lowpassFilterApplyFn;
gyroLowpassFilter_t *lowpassFilter = NULL;
switch (slot) {
case FILTER_LOWPASS:
lowpassFilterApplyFn = &gyro.lowpassFilterApplyFn;
lowpassFilter = gyro.lowpassFilter;
break;
case FILTER_LOWPASS2:
lowpassFilterApplyFn = &gyro.lowpass2FilterApplyFn;
lowpassFilter = gyro.lowpass2Filter;
break;
default:
return false;
}
bool ret = false;
// Establish some common constants
const uint32_t gyroFrequencyNyquist = 1000000 / 2 / looptime;
const float gyroDt = looptime * 1e-6f;
// Gain could be calculated a little later as it is specific to the pt1/bqrcf2/fkf branches
const float gain = pt1FilterGain(lpfHz, gyroDt);
// Dereference the pointer to null before checking valid cutoff and filter
// type. It will be overridden for positive cases.
*lowpassFilterApplyFn = nullFilterApply;
// If lowpass cutoff has been specified and is less than the Nyquist frequency
if (lpfHz && lpfHz <= gyroFrequencyNyquist) {
switch (type) {
case FILTER_PT1:
*lowpassFilterApplyFn = (filterApplyFnPtr) pt1FilterApply;
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
pt1FilterInit(&lowpassFilter[axis].pt1FilterState, gain);
}
ret = true;
break;
case FILTER_BIQUAD:
#ifdef USE_DYN_LPF
*lowpassFilterApplyFn = (filterApplyFnPtr) biquadFilterApplyDF1;
#else
*lowpassFilterApplyFn = (filterApplyFnPtr) biquadFilterApply;
#endif
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
biquadFilterInitLPF(&lowpassFilter[axis].biquadFilterState, lpfHz, looptime);
}
ret = true;
break;
}
}
return ret;
}
#ifdef USE_DYN_LPF
static void dynLpfFilterInit()
{
if (gyroConfig()->dyn_lpf_gyro_min_hz > 0) {
switch (gyroConfig()->gyro_lowpass_type) {
case FILTER_PT1:
gyro.dynLpfFilter = DYN_LPF_PT1;
break;
case FILTER_BIQUAD:
gyro.dynLpfFilter = DYN_LPF_BIQUAD;
break;
default:
gyro.dynLpfFilter = DYN_LPF_NONE;
break;
}
} else {
gyro.dynLpfFilter = DYN_LPF_NONE;
}
gyro.dynLpfMin = gyroConfig()->dyn_lpf_gyro_min_hz;
gyro.dynLpfMax = gyroConfig()->dyn_lpf_gyro_max_hz;
}
#endif
void gyroInitFilters(void)
{
uint16_t gyro_lowpass_hz = gyroConfig()->gyro_lowpass_hz;
#ifdef USE_DYN_LPF
if (gyroConfig()->dyn_lpf_gyro_min_hz > 0) {
gyro_lowpass_hz = gyroConfig()->dyn_lpf_gyro_min_hz;
}
#endif
gyroInitLowpassFilterLpf(
FILTER_LOWPASS,
gyroConfig()->gyro_lowpass_type,
gyro_lowpass_hz,
gyro.targetLooptime
);
gyro.downsampleFilterEnabled = gyroInitLowpassFilterLpf(
FILTER_LOWPASS2,
gyroConfig()->gyro_lowpass2_type,
gyroConfig()->gyro_lowpass2_hz,
gyro.sampleLooptime
);
gyroInitFilterNotch1(gyroConfig()->gyro_soft_notch_hz_1, gyroConfig()->gyro_soft_notch_cutoff_1);
gyroInitFilterNotch2(gyroConfig()->gyro_soft_notch_hz_2, gyroConfig()->gyro_soft_notch_cutoff_2);
#ifdef USE_GYRO_DATA_ANALYSE
gyroInitFilterDynamicNotch();
#endif
#ifdef USE_DYN_LPF
dynLpfFilterInit();
#endif
#ifdef USE_GYRO_DATA_ANALYSE
gyroDataAnalyseStateInit(&gyro.gyroAnalyseState, gyro.targetLooptime);
#endif
}
#if defined(USE_GYRO_SLEW_LIMITER)
void gyroInitSlewLimiter(gyroSensor_t *gyroSensor) {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
gyroSensor->gyroDev.gyroADCRawPrevious[axis] = 0;
}
}
#endif
static void gyroInitSensorFilters(gyroSensor_t *gyroSensor)
{
#if defined(USE_GYRO_SLEW_LIMITER)
gyroInitSlewLimiter(gyroSensor);
#else
UNUSED(gyroSensor);
#endif
}
void gyroInitSensor(gyroSensor_t *gyroSensor, const gyroDeviceConfig_t *config)
{
gyroSensor->gyroDev.gyro_high_fsr = gyroConfig()->gyro_high_fsr;
gyroSensor->gyroDev.gyroAlign = config->alignment;
buildRotationMatrixFromAlignment(&config->customAlignment, &gyroSensor->gyroDev.rotationMatrix);
gyroSensor->gyroDev.mpuIntExtiTag = config->extiTag;
gyroSensor->gyroDev.hardware_lpf = gyroConfig()->gyro_hardware_lpf;
// The targetLooptime gets set later based on the active sensor's gyroSampleRateHz and pid_process_denom
gyroSensor->gyroDev.gyroSampleRateHz = gyroSetSampleRate(&gyroSensor->gyroDev);
gyroSensor->gyroDev.initFn(&gyroSensor->gyroDev);
// As new gyros are supported, be sure to add them below based on whether they are subject to the overflow/inversion bug
// Any gyro not explicitly defined will default to not having built-in overflow protection as a safe alternative.
switch (gyroSensor->gyroDev.gyroHardware) {
case GYRO_NONE: // Won't ever actually get here, but included to account for all gyro types
case GYRO_DEFAULT:
case GYRO_FAKE:
case GYRO_MPU6050:
case GYRO_L3G4200D:
case GYRO_MPU3050:
case GYRO_L3GD20:
case GYRO_BMI160:
case GYRO_BMI270:
case GYRO_MPU6000:
case GYRO_MPU6500:
case GYRO_MPU9250:
gyroSensor->gyroDev.gyroHasOverflowProtection = true;
break;
case GYRO_ICM20601:
case GYRO_ICM20602:
case GYRO_ICM20608G:
case GYRO_ICM20649: // we don't actually know if this is affected, but as there are currently no flight controllers using it we err on the side of caution
case GYRO_ICM20689:
gyroSensor->gyroDev.gyroHasOverflowProtection = false;
break;
default:
gyroSensor->gyroDev.gyroHasOverflowProtection = false; // default catch for newly added gyros until proven to be unaffected
break;
}
gyroInitSensorFilters(gyroSensor);
}
STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev)
{
gyroHardware_e gyroHardware = GYRO_DEFAULT;
switch (gyroHardware) {
case GYRO_DEFAULT:
FALLTHROUGH;
#ifdef USE_GYRO_MPU6050
case GYRO_MPU6050:
if (mpu6050GyroDetect(dev)) {
gyroHardware = GYRO_MPU6050;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_L3G4200D
case GYRO_L3G4200D:
if (l3g4200dDetect(dev)) {
gyroHardware = GYRO_L3G4200D;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_MPU3050
case GYRO_MPU3050:
if (mpu3050Detect(dev)) {
gyroHardware = GYRO_MPU3050;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_L3GD20
case GYRO_L3GD20:
if (l3gd20GyroDetect(dev)) {
gyroHardware = GYRO_L3GD20;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_SPI_MPU6000
case GYRO_MPU6000:
if (mpu6000SpiGyroDetect(dev)) {
gyroHardware = GYRO_MPU6000;
break;
}
FALLTHROUGH;
#endif
#if defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500)
case GYRO_MPU6500:
case GYRO_ICM20601:
case GYRO_ICM20602:
case GYRO_ICM20608G:
#ifdef USE_GYRO_SPI_MPU6500
if (mpu6500GyroDetect(dev) || mpu6500SpiGyroDetect(dev)) {
#else
if (mpu6500GyroDetect(dev)) {
#endif
switch (dev->mpuDetectionResult.sensor) {
case MPU_9250_SPI:
gyroHardware = GYRO_MPU9250;
break;
case ICM_20601_SPI:
gyroHardware = GYRO_ICM20601;
break;
case ICM_20602_SPI:
gyroHardware = GYRO_ICM20602;
break;
case ICM_20608_SPI:
gyroHardware = GYRO_ICM20608G;
break;
default:
gyroHardware = GYRO_MPU6500;
}
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_SPI_MPU9250
case GYRO_MPU9250:
if (mpu9250SpiGyroDetect(dev)) {
gyroHardware = GYRO_MPU9250;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_SPI_ICM20649
case GYRO_ICM20649:
if (icm20649SpiGyroDetect(dev)) {
gyroHardware = GYRO_ICM20649;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_SPI_ICM20689
case GYRO_ICM20689:
if (icm20689SpiGyroDetect(dev)) {
gyroHardware = GYRO_ICM20689;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_GYRO_SPI_ICM42605
case GYRO_ICM42605:
if (icm42605SpiGyroDetect(dev)) {
gyroHardware = GYRO_ICM42605;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_ACCGYRO_BMI160
case GYRO_BMI160:
if (bmi160SpiGyroDetect(dev)) {
gyroHardware = GYRO_BMI160;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_ACCGYRO_BMI270
case GYRO_BMI270:
if (bmi270SpiGyroDetect(dev)) {
gyroHardware = GYRO_BMI270;
break;
}
FALLTHROUGH;
#endif
#ifdef USE_FAKE_GYRO
case GYRO_FAKE:
if (fakeGyroDetect(dev)) {
gyroHardware = GYRO_FAKE;
break;
}
FALLTHROUGH;
#endif
default:
gyroHardware = GYRO_NONE;
}
if (gyroHardware != GYRO_NONE) {
sensorsSet(SENSOR_GYRO);
}
return gyroHardware;
}
static bool gyroDetectSensor(gyroSensor_t *gyroSensor, const gyroDeviceConfig_t *config)
{
#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) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) \
|| defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_L3GD20) || defined(USE_ACCGYRO_BMI160) || defined(USE_ACCGYRO_BMI270)
bool gyroFound = mpuDetect(&gyroSensor->gyroDev, config);
#if !defined(USE_FAKE_GYRO) // Allow resorting to fake accgyro if defined
if (!gyroFound) {
return false;
}
#else
UNUSED(gyroFound);
#endif
#else
UNUSED(config);
#endif
const gyroHardware_e gyroHardware = gyroDetect(&gyroSensor->gyroDev);
gyroSensor->gyroDev.gyroHardware = gyroHardware;
return gyroHardware != GYRO_NONE;
}
static void gyroPreInitSensor(const gyroDeviceConfig_t *config)
{
#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) || defined(USE_GYRO_SPI_ICM20601) || defined(USE_GYRO_SPI_ICM20649) \
|| defined(USE_GYRO_SPI_ICM20689) || defined(USE_ACCGYRO_BMI160) || defined(USE_ACCGYRO_BMI270)
mpuPreInit(config);
#else
UNUSED(config);
#endif
}
void gyroPreInit(void)
{
gyroPreInitSensor(gyroDeviceConfig(0));
#ifdef USE_MULTI_GYRO
gyroPreInitSensor(gyroDeviceConfig(1));
#endif
}
bool gyroInit(void)
{
#ifdef USE_GYRO_OVERFLOW_CHECK
if (gyroConfig()->checkOverflow == GYRO_OVERFLOW_CHECK_YAW) {
gyro.overflowAxisMask = GYRO_OVERFLOW_Z;
} else if (gyroConfig()->checkOverflow == GYRO_OVERFLOW_CHECK_ALL_AXES) {
gyro.overflowAxisMask = GYRO_OVERFLOW_X | GYRO_OVERFLOW_Y | GYRO_OVERFLOW_Z;
} else {
gyro.overflowAxisMask = 0;
}
#endif
gyro.gyroDebugMode = DEBUG_NONE;
gyro.useDualGyroDebugging = false;
gyro.gyroHasOverflowProtection = true;
switch (debugMode) {
case DEBUG_FFT:
case DEBUG_FFT_FREQ:
case DEBUG_GYRO_RAW:
case DEBUG_GYRO_SCALED:
case DEBUG_GYRO_FILTERED:
case DEBUG_DYN_LPF:
case DEBUG_GYRO_SAMPLE:
gyro.gyroDebugMode = debugMode;
break;
case DEBUG_DUAL_GYRO_DIFF:
case DEBUG_DUAL_GYRO_RAW:
case DEBUG_DUAL_GYRO_SCALED:
gyro.useDualGyroDebugging = true;
break;
}
gyroDetectionFlags = NO_GYROS_DETECTED;
gyro.gyroToUse = gyroConfig()->gyro_to_use;
gyro.gyroDebugAxis = gyroConfig()->gyro_filter_debug_axis;
if (gyroDetectSensor(&gyro.gyroSensor1, gyroDeviceConfig(0))) {
gyroDetectionFlags |= DETECTED_GYRO_1;
}
#if defined(USE_MULTI_GYRO)
if (gyroDetectSensor(&gyro.gyroSensor2, gyroDeviceConfig(1))) {
gyroDetectionFlags |= DETECTED_GYRO_2;
}
#endif
if (gyroDetectionFlags == NO_GYROS_DETECTED) {
return false;
}
#if defined(USE_MULTI_GYRO)
if ((gyro.gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH && !((gyroDetectionFlags & DETECTED_BOTH_GYROS) == DETECTED_BOTH_GYROS))
|| (gyro.gyroToUse == GYRO_CONFIG_USE_GYRO_1 && !(gyroDetectionFlags & DETECTED_GYRO_1))
|| (gyro.gyroToUse == GYRO_CONFIG_USE_GYRO_2 && !(gyroDetectionFlags & DETECTED_GYRO_2))) {
if (gyroDetectionFlags & DETECTED_GYRO_1) {
gyro.gyroToUse = GYRO_CONFIG_USE_GYRO_1;
} else {
gyro.gyroToUse = GYRO_CONFIG_USE_GYRO_2;
}
gyroConfigMutable()->gyro_to_use = gyro.gyroToUse;
}
// Only allow using both gyros simultaneously if they are the same hardware type.
if (((gyroDetectionFlags & DETECTED_BOTH_GYROS) == DETECTED_BOTH_GYROS) && gyro.gyroSensor1.gyroDev.gyroHardware == gyro.gyroSensor2.gyroDev.gyroHardware) {
gyroDetectionFlags |= DETECTED_DUAL_GYROS;
} else if (gyro.gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
// If the user selected "BOTH" and they are not the same type, then reset to using only the first gyro.
gyro.gyroToUse = GYRO_CONFIG_USE_GYRO_1;
gyroConfigMutable()->gyro_to_use = gyro.gyroToUse;
}
if (gyro.gyroToUse == GYRO_CONFIG_USE_GYRO_2 || gyro.gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
gyroInitSensor(&gyro.gyroSensor2, gyroDeviceConfig(1));
gyro.gyroHasOverflowProtection = gyro.gyroHasOverflowProtection && gyro.gyroSensor2.gyroDev.gyroHasOverflowProtection;
detectedSensors[SENSOR_INDEX_GYRO] = gyro.gyroSensor2.gyroDev.gyroHardware;
}
#endif
if (gyro.gyroToUse == GYRO_CONFIG_USE_GYRO_1 || gyro.gyroToUse == GYRO_CONFIG_USE_GYRO_BOTH) {
gyroInitSensor(&gyro.gyroSensor1, gyroDeviceConfig(0));
gyro.gyroHasOverflowProtection = gyro.gyroHasOverflowProtection && gyro.gyroSensor1.gyroDev.gyroHasOverflowProtection;
detectedSensors[SENSOR_INDEX_GYRO] = gyro.gyroSensor1.gyroDev.gyroHardware;
}
// Copy the sensor's scale to the high-level gyro object. If running in "BOTH" mode
// then logic above requires both sensors to be the same so we'll use sensor1's scale.
// This will need to be revised if we ever allow different sensor types to be used simultaneously.
// Likewise determine the appropriate raw data for use in DEBUG_GYRO_RAW
gyro.scale = gyro.gyroSensor1.gyroDev.scale;
gyro.rawSensorDev = &gyro.gyroSensor1.gyroDev;
#if defined(USE_MULTI_GYRO)
if (gyro.gyroToUse == GYRO_CONFIG_USE_GYRO_2) {
gyro.scale = gyro.gyroSensor2.gyroDev.scale;
gyro.rawSensorDev = &gyro.gyroSensor2.gyroDev;
}
#endif
if (gyro.rawSensorDev) {
gyro.sampleRateHz = gyro.rawSensorDev->gyroSampleRateHz;
gyro.accSampleRateHz = gyro.rawSensorDev->accSampleRateHz;
} else {
gyro.sampleRateHz = 0;
gyro.accSampleRateHz = 0;
}
return true;
}
gyroDetectionFlags_t getGyroDetectionFlags(void)
{
return gyroDetectionFlags;
}
void gyroSetTargetLooptime(uint8_t pidDenom)
{
activePidLoopDenom = pidDenom;
if (gyro.sampleRateHz) {
gyro.sampleLooptime = 1e6 / gyro.sampleRateHz;
gyro.targetLooptime = activePidLoopDenom * 1e6 / gyro.sampleRateHz;
} else {
gyro.sampleLooptime = 0;
gyro.targetLooptime = 0;
}
}
const busDevice_t *gyroSensorBus(void)
{
return &ACTIVE_GYRO->gyroDev.bus;
}
const mpuDetectionResult_t *gyroMpuDetectionResult(void)
{
return &ACTIVE_GYRO->gyroDev.mpuDetectionResult;
}
int16_t gyroRateDps(int axis)
{
return lrintf(gyro.gyroADCf[axis] / ACTIVE_GYRO->gyroDev.scale);
}
#ifdef USE_GYRO_REGISTER_DUMP
static const busDevice_t *gyroSensorBusByDevice(uint8_t whichSensor)
{
#ifdef USE_MULTI_GYRO
if (whichSensor == GYRO_CONFIG_USE_GYRO_2) {
return &gyro.gyroSensor2.gyroDev.bus;
}
#else
UNUSED(whichSensor);
#endif
return &gyro.gyroSensor1.gyroDev.bus;
}
uint8_t gyroReadRegister(uint8_t whichSensor, uint8_t reg)
{
return mpuGyroReadRegister(gyroSensorBusByDevice(whichSensor), reg);
}
#endif // USE_GYRO_REGISTER_DUMP

View File

@ -0,0 +1,36 @@
/*
* 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)
* any later version.
*
* 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.
* 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.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "pg/gyrodev.h"
#include "sensors/gyro.h"
void gyroSetTargetLooptime(uint8_t pidDenom);
void gyroPreInit(void);
bool gyroInit(void);
void gyroInitFilters(void);
void gyroInitSensor(gyroSensor_t *gyroSensor, const gyroDeviceConfig_t *config);
gyroDetectionFlags_t getGyroDetectionFlags(void);
const busDevice_t *gyroSensorBus(void);
struct mpuDetectionResult_s;
const struct mpuDetectionResult_s *gyroMpuDetectionResult(void);
int16_t gyroRateDps(int axis);
uint8_t gyroReadRegister(uint8_t whichSensor, uint8_t reg);

View File

@ -26,23 +26,25 @@
#include "common/utils.h"
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "config/config.h"
#include "config/feature.h"
#include "fc/runtime_config.h"
#include "flight/pid.h"
#include "sensors/sensors.h"
#include "sensors/adcinternal.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "sensors/acceleration.h"
#include "sensors/adcinternal.h"
#include "sensors/barometer.h"
#include "sensors/gyro.h"
#include "sensors/compass.h"
#include "sensors/rangefinder.h"
#include "sensors/gyro.h"
#include "sensors/gyro_init.h"
#include "sensors/initialisation.h"
#include "sensors/rangefinder.h"
#include "sensors/sensors.h"
// requestedSensors is not actually used
uint8_t requestedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE, RANGEFINDER_NONE };

View File

@ -277,6 +277,7 @@ scheduler_unittest_SRC := \
sensor_gyro_unittest_SRC := \
$(USER_DIR)/sensors/gyro.c \
$(USER_DIR)/sensors/gyro_init.c \
$(USER_DIR)/sensors/boardalignment.c \
$(USER_DIR)/common/filter.c \
$(USER_DIR)/common/maths.c \

View File

@ -37,6 +37,7 @@ extern "C" {
#include "pg/pg_ids.h"
#include "scheduler/scheduler.h"
#include "sensors/gyro.h"
#include "sensors/gyro_init.h"
#include "sensors/acceleration.h"
#include "sensors/sensors.h"