Set blackbox file handler to NULL after closing file
[inav.git] / src / main / sensors / gyro.h
blobde78b2f81c2b9947f8ad70b9dbb7aa03e7f97f24
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #pragma once
20 #include "common/axis.h"
21 #include "common/maths.h"
22 #include "common/vector.h"
23 #include "common/time.h"
24 #include "config/parameter_group.h"
25 #include "drivers/sensor.h"
26 #include "flight/dynamic_gyro_notch.h"
27 #include "flight/secondary_dynamic_gyro_notch.h"
28 #if !defined(SITL_BUILD)
29 #include "arm_math.h"
30 #else
31 #include <math.h>
32 #endif
34 typedef enum {
35 GYRO_NONE = 0,
36 GYRO_AUTODETECT,
37 GYRO_MPU6000,
38 GYRO_MPU6500,
39 GYRO_MPU9250,
40 GYRO_BMI160,
41 GYRO_ICM20689,
42 GYRO_BMI088,
43 GYRO_ICM42605,
44 GYRO_BMI270,
45 GYRO_LSM6DXX,
46 GYRO_FAKE
48 } gyroSensor_e;
50 typedef enum {
51 DYNAMIC_NOTCH_MODE_2D = 0,
52 DYNAMIC_NOTCH_MODE_3D
53 } dynamicGyroNotchMode_e;
55 typedef enum {
56 GYRO_FILTER_MODE_OFF = 0,
57 GYRO_FILTER_MODE_STATIC = 1,
58 GYRO_FILTER_MODE_DYNAMIC = 2,
59 GYRO_FILTER_MODE_ADAPTIVE = 3
60 } gyroFilterMode_e;
62 typedef struct gyro_s {
63 bool initialized;
64 uint32_t targetLooptime;
65 float gyroADCf[XYZ_AXIS_COUNT];
66 float gyroRaw[XYZ_AXIS_COUNT];
67 } gyro_t;
69 extern gyro_t gyro;
70 extern dynamicGyroNotchState_t dynamicGyroNotchState;
72 typedef struct gyroConfig_s {
73 uint16_t looptime; // imu loop time in us
74 uint16_t gyro_anti_aliasing_lpf_hz;
75 #ifdef USE_DUAL_GYRO
76 uint8_t gyro_to_use;
77 #endif
78 uint16_t gyro_main_lpf_hz;
79 uint16_t gyroDynamicLpfMinHz;
80 uint16_t gyroDynamicLpfMaxHz;
81 uint8_t gyroDynamicLpfCurveExpo;
82 #ifdef USE_DYNAMIC_FILTERS
83 uint16_t dynamicGyroNotchQ;
84 uint16_t dynamicGyroNotchMinHz;
85 uint8_t dynamicGyroNotchEnabled;
86 uint8_t dynamicGyroNotchMode;
87 uint16_t dynamicGyroNotch3dQ;
88 #endif
89 #ifdef USE_GYRO_KALMAN
90 uint16_t kalman_q;
91 uint8_t kalmanEnabled;
92 #endif
93 bool init_gyro_cal_enabled;
94 int16_t gyro_zero_cal[XYZ_AXIS_COUNT];
95 float gravity_cmss_cal;
96 #ifdef USE_ADAPTIVE_FILTER
97 float adaptiveFilterTarget;
98 uint16_t adaptiveFilterMinHz;
99 uint16_t adaptiveFilterMaxHz;
100 float adaptiveFilterStdLpfHz;
101 float adaptiveFilterHpfHz;
102 float adaptiveFilterIntegratorThresholdHigh;
103 float adaptiveFilterIntegratorThresholdLow;
104 #endif
105 uint8_t gyroFilterMode;
107 uint8_t gyroLuluSampleCount;
108 bool gyroLuluEnabled;
109 } gyroConfig_t;
111 PG_DECLARE(gyroConfig_t, gyroConfig);
113 bool gyroInit(void);
114 void gyroGetMeasuredRotationRate(fpVector3_t *imuMeasuredRotationBF);
115 void gyroUpdate(void);
116 void gyroFilter(void);
117 void gyroStartCalibration(void);
118 bool gyroIsCalibrationComplete(void);
119 bool gyroReadTemperature(void);
120 int16_t gyroGetTemperature(void);
121 int16_t gyroRateDps(int axis);
122 void gyroUpdateDynamicLpf(float cutoffFreq);
123 float averageAbsGyroRates(void);