Update gyroregisters cli command to display both gyros
[betaflight.git] / src / main / sensors / gyro.h
blobf26d7673d8c8a7b37b52f2f277afd4f6ed8f6d92
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/time.h"
25 #include "pg/pg.h"
26 #include "drivers/bus.h"
27 #include "drivers/sensor.h"
29 typedef enum {
30 GYRO_NONE = 0,
31 GYRO_DEFAULT,
32 GYRO_MPU6050,
33 GYRO_L3G4200D,
34 GYRO_MPU3050,
35 GYRO_L3GD20,
36 GYRO_MPU6000,
37 GYRO_MPU6500,
38 GYRO_MPU9250,
39 GYRO_ICM20601,
40 GYRO_ICM20602,
41 GYRO_ICM20608G,
42 GYRO_ICM20649,
43 GYRO_ICM20689,
44 GYRO_BMI160,
45 GYRO_FAKE
46 } gyroSensor_e;
48 typedef struct gyro_s {
49 uint32_t targetLooptime;
50 float gyroADCf[XYZ_AXIS_COUNT];
51 } gyro_t;
53 extern gyro_t gyro;
55 typedef enum {
56 GYRO_OVERFLOW_CHECK_NONE = 0,
57 GYRO_OVERFLOW_CHECK_YAW,
58 GYRO_OVERFLOW_CHECK_ALL_AXES
59 } gyroOverflowCheck_e;
61 #define GYRO_CONFIG_USE_GYRO_1 0
62 #define GYRO_CONFIG_USE_GYRO_2 1
63 #define GYRO_CONFIG_USE_GYRO_BOTH 2
65 typedef enum {
66 FILTER_LOWPASS = 0,
67 FILTER_LOWPASS2
68 } filterSlots;
70 #define GYRO_LPF_ORDER_MAX 6
72 typedef struct gyroConfig_s {
73 sensor_align_e gyro_align; // gyro alignment
74 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.
75 uint8_t gyro_sync_denom; // Gyro sample divider
76 uint8_t gyro_hardware_lpf; // gyro DLPF setting
77 uint8_t gyro_32khz_hardware_lpf; // gyro 32khz DLPF setting
79 bool gyro_high_fsr;
80 bool gyro_use_32khz;
81 uint8_t gyro_to_use;
83 // Lagged Moving Average smoother
84 uint8_t gyro_lma_depth;
85 uint8_t gyro_lma_weight;
87 // Lowpass primary/secondary
88 uint8_t gyro_lowpass_type;
89 uint8_t gyro_lowpass2_type;
91 // Order is used for the 'higher ordering' of cascaded butterworth/biquad sections
92 uint8_t gyro_lowpass_order;
93 uint8_t gyro_lowpass2_order;
95 uint16_t gyro_lowpass_hz;
96 uint16_t gyro_lowpass2_hz;
98 uint16_t gyro_soft_notch_hz_1;
99 uint16_t gyro_soft_notch_cutoff_1;
100 uint16_t gyro_soft_notch_hz_2;
101 uint16_t gyro_soft_notch_cutoff_2;
102 gyroOverflowCheck_e checkOverflow;
103 int16_t gyro_offset_yaw;
105 bool yaw_spin_recovery;
106 int16_t yaw_spin_threshold;
108 } gyroConfig_t;
110 PG_DECLARE(gyroConfig_t, gyroConfig);
112 bool gyroInit(void);
114 void gyroInitFilters(void);
115 void gyroUpdate(timeUs_t currentTimeUs);
116 bool gyroGetAccumulationAverage(float *accumulation);
117 const busDevice_t *gyroSensorBus(void);
118 struct mpuConfiguration_s;
119 const struct mpuConfiguration_s *gyroMpuConfiguration(void);
120 struct mpuDetectionResult_s;
121 const struct mpuDetectionResult_s *gyroMpuDetectionResult(void);
122 void gyroStartCalibration(bool isFirstArmingCalibration);
123 bool isFirstArmingGyroCalibrationRunning(void);
124 bool isGyroCalibrationComplete(void);
125 void gyroReadTemperature(void);
126 int16_t gyroGetTemperature(void);
127 int16_t gyroRateDps(int axis);
128 bool gyroOverflowDetected(void);
129 bool gyroYawSpinDetected(void);
130 uint16_t gyroAbsRateDps(int axis);
131 uint8_t gyroReadRegister(uint8_t whichSensor, uint8_t reg);