Merge pull request #11500 from klutvott123/crsf-baud-negotiation-improvements-2
[betaflight.git] / src / main / sensors / gyro.h
blob5ff3eb88896192a73eccf32b693bb980746f3ad9
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 #pragma once
23 #include "common/axis.h"
24 #include "common/filter.h"
25 #include "common/time.h"
26 #include "common/utils.h"
28 #include "drivers/accgyro/accgyro.h"
29 #include "drivers/bus.h"
30 #include "drivers/sensor.h"
32 #ifdef USE_DYN_NOTCH_FILTER
33 #include "flight/dyn_notch_filter.h"
34 #endif
36 #include "flight/pid.h"
38 #include "pg/pg.h"
40 #define LPF_MAX_HZ 1000 // so little filtering above 1000hz that if the user wants less delay, they must disable the filter
41 #define DYN_LPF_MAX_HZ 1000
43 #define GYRO_LPF1_DYN_MIN_HZ_DEFAULT 250
44 #define GYRO_LPF1_DYN_MAX_HZ_DEFAULT 500
45 #define GYRO_LPF2_HZ_DEFAULT 500
47 #ifdef USE_YAW_SPIN_RECOVERY
48 #define YAW_SPIN_RECOVERY_THRESHOLD_MIN 500
49 #define YAW_SPIN_RECOVERY_THRESHOLD_MAX 1950
50 #endif
52 typedef union gyroLowpassFilter_u {
53 pt1Filter_t pt1FilterState;
54 biquadFilter_t biquadFilterState;
55 pt2Filter_t pt2FilterState;
56 pt3Filter_t pt3FilterState;
57 } gyroLowpassFilter_t;
59 typedef enum gyroDetectionFlags_e {
60 GYRO_NONE_MASK = 0,
61 GYRO_1_MASK = BIT(0),
62 #if defined(USE_MULTI_GYRO)
63 GYRO_2_MASK = BIT(1),
64 GYRO_ALL_MASK = (GYRO_1_MASK | GYRO_2_MASK),
65 GYRO_IDENTICAL_MASK = BIT(7), // All gyros are of the same hardware type
66 #endif
67 } gyroDetectionFlags_t;
69 typedef struct gyroCalibration_s {
70 float sum[XYZ_AXIS_COUNT];
71 stdev_t var[XYZ_AXIS_COUNT];
72 int32_t cyclesRemaining;
73 } gyroCalibration_t;
75 typedef struct gyroSensor_s {
76 gyroDev_t gyroDev;
77 gyroCalibration_t calibration;
78 } gyroSensor_t;
80 typedef struct gyro_s {
81 uint16_t sampleRateHz;
82 uint32_t targetLooptime;
83 uint32_t sampleLooptime;
84 float scale;
85 float gyroADC[XYZ_AXIS_COUNT]; // aligned, calibrated, scaled, but unfiltered data from the sensor(s)
86 float gyroADCf[XYZ_AXIS_COUNT]; // filtered gyro data
87 uint8_t sampleCount; // gyro sensor sample counter
88 float sampleSum[XYZ_AXIS_COUNT]; // summed samples used for downsampling
89 bool downsampleFilterEnabled; // if true then downsample using gyro lowpass 2, otherwise use averaging
91 gyroSensor_t gyroSensor1;
92 #ifdef USE_MULTI_GYRO
93 gyroSensor_t gyroSensor2;
94 #endif
96 gyroDev_t *rawSensorDev; // pointer to the sensor providing the raw data for DEBUG_GYRO_RAW
98 // lowpass gyro soft filter
99 filterApplyFnPtr lowpassFilterApplyFn;
100 gyroLowpassFilter_t lowpassFilter[XYZ_AXIS_COUNT];
102 // lowpass2 gyro soft filter
103 filterApplyFnPtr lowpass2FilterApplyFn;
104 gyroLowpassFilter_t lowpass2Filter[XYZ_AXIS_COUNT];
106 // notch filters
107 filterApplyFnPtr notchFilter1ApplyFn;
108 biquadFilter_t notchFilter1[XYZ_AXIS_COUNT];
110 filterApplyFnPtr notchFilter2ApplyFn;
111 biquadFilter_t notchFilter2[XYZ_AXIS_COUNT];
113 uint16_t accSampleRateHz;
114 uint8_t gyroToUse;
115 uint8_t gyroDebugMode;
116 bool gyroHasOverflowProtection;
117 bool useDualGyroDebugging;
118 flight_dynamics_index_t gyroDebugAxis;
120 #ifdef USE_DYN_LPF
121 uint8_t dynLpfFilter;
122 uint16_t dynLpfMin;
123 uint16_t dynLpfMax;
124 uint8_t dynLpfCurveExpo;
125 #endif
127 #ifdef USE_GYRO_OVERFLOW_CHECK
128 uint8_t overflowAxisMask;
129 #endif
131 } gyro_t;
133 extern gyro_t gyro;
134 extern uint8_t activePidLoopDenom;
136 enum {
137 GYRO_OVERFLOW_CHECK_NONE = 0,
138 GYRO_OVERFLOW_CHECK_YAW,
139 GYRO_OVERFLOW_CHECK_ALL_AXES
142 enum {
143 DYN_LPF_NONE = 0,
144 DYN_LPF_PT1,
145 DYN_LPF_BIQUAD,
146 DYN_LPF_PT2,
147 DYN_LPF_PT3,
150 typedef enum {
151 YAW_SPIN_RECOVERY_OFF,
152 YAW_SPIN_RECOVERY_ON,
153 YAW_SPIN_RECOVERY_AUTO
154 } yawSpinRecoveryMode_e;
156 #define GYRO_CONFIG_USE_GYRO_1 0
157 #define GYRO_CONFIG_USE_GYRO_2 1
158 #define GYRO_CONFIG_USE_GYRO_BOTH 2
160 enum {
161 FILTER_LPF1 = 0,
162 FILTER_LPF2
165 typedef struct gyroConfig_s {
166 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.
167 uint8_t gyro_hardware_lpf; // gyro DLPF setting
168 uint8_t gyro_high_fsr;
169 uint8_t gyro_to_use;
171 uint16_t gyro_lpf1_static_hz;
172 uint16_t gyro_lpf2_static_hz;
174 uint16_t gyro_soft_notch_hz_1;
175 uint16_t gyro_soft_notch_cutoff_1;
176 uint16_t gyro_soft_notch_hz_2;
177 uint16_t gyro_soft_notch_cutoff_2;
178 int16_t gyro_offset_yaw;
179 uint8_t checkOverflow;
181 // Lowpass primary/secondary
182 uint8_t gyro_lpf1_type;
183 uint8_t gyro_lpf2_type;
185 uint8_t yaw_spin_recovery;
186 int16_t yaw_spin_threshold;
188 uint16_t gyroCalibrationDuration; // Gyro calibration duration in 1/100 second
190 uint16_t gyro_lpf1_dyn_min_hz;
191 uint16_t gyro_lpf1_dyn_max_hz;
193 uint8_t gyro_filter_debug_axis;
195 uint8_t gyrosDetected; // What gyros should detection be attempted for on startup. Automatically set on first startup.
196 uint8_t gyro_lpf1_dyn_expo; // set the curve for dynamic gyro lowpass filter
197 uint8_t simplified_gyro_filter;
198 uint8_t simplified_gyro_filter_multiplier;
199 } gyroConfig_t;
201 PG_DECLARE(gyroConfig_t, gyroConfig);
203 void gyroUpdate(void);
204 void gyroFiltering(timeUs_t currentTimeUs);
205 bool gyroGetAccumulationAverage(float *accumulation);
206 void gyroStartCalibration(bool isFirstArmingCalibration);
207 bool isFirstArmingGyroCalibrationRunning(void);
208 bool gyroIsCalibrationComplete(void);
209 void gyroReadTemperature(void);
210 int16_t gyroGetTemperature(void);
211 bool gyroOverflowDetected(void);
212 bool gyroYawSpinDetected(void);
213 uint16_t gyroAbsRateDps(int axis);
214 #ifdef USE_DYN_LPF
215 float dynThrottle(float throttle);
216 void dynLpfGyroUpdate(float throttle);
217 #endif
218 #ifdef USE_YAW_SPIN_RECOVERY
219 void initYawSpinRecovery(int maxYawRate);
220 #endif