osd batt cleanup
[inav.git] / src / main / sensors / acceleration.h
blobaa9ef737542d986245e324d6cf7ec3cc4a327dc0
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 "config/parameter_group.h"
24 #include "drivers/accgyro/accgyro.h"
25 #include "sensors/sensors.h"
27 #define GRAVITY_CMSS 980.665f
28 #define GRAVITY_MSS 9.80665f
30 #define ACC_CLIPPING_THRESHOLD_G 7.9f
31 #define ACC_VIBE_FLOOR_FILT_HZ 5.0f
32 #define ACC_VIBE_FILT_HZ 2.0f
34 // Type of accelerometer used/detected
35 typedef enum {
36 ACC_NONE = 0,
37 ACC_AUTODETECT,
38 ACC_MPU6000,
39 ACC_MPU6500,
40 ACC_MPU9250,
41 ACC_BMI160,
42 ACC_ICM20689,
43 ACC_BMI088,
44 ACC_ICM42605,
45 ACC_BMI270,
46 ACC_FAKE,
47 ACC_MAX = ACC_FAKE
48 } accelerationSensor_e;
50 typedef struct {
51 float min;
52 float max;
53 } acc_extremes_t;
55 typedef struct acc_s {
56 accDev_t dev;
57 uint32_t accTargetLooptime;
58 float accADCf[XYZ_AXIS_COUNT]; // acceleration in g
59 float accVibeSq[XYZ_AXIS_COUNT];
60 uint32_t accClipCount;
61 bool isClipped;
62 acc_extremes_t extremes[XYZ_AXIS_COUNT];
63 float maxG;
64 } acc_t;
66 extern acc_t acc;
68 typedef struct accelerometerConfig_s {
69 uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
70 uint16_t acc_lpf_hz; // cutoff frequency for the low pass filter used on the acc z-axis for althold in Hz
71 flightDynamicsTrims_t accZero; // Accelerometer offset
72 flightDynamicsTrims_t accGain; // Accelerometer gain to read exactly 1G
73 uint8_t acc_notch_hz; // Accelerometer notch filter frequency
74 uint8_t acc_notch_cutoff; // Accelerometer notch filter cutoff frequency
75 uint8_t acc_soft_lpf_type; // Accelerometer LPF type
76 } accelerometerConfig_t;
78 PG_DECLARE(accelerometerConfig_t, accelerometerConfig);
80 bool accInit(uint32_t accTargetLooptime);
81 bool accIsCalibrationComplete(void);
82 void accStartCalibration(void);
83 void accGetMeasuredAcceleration(fpVector3_t *measuredAcc);
84 const acc_extremes_t* accGetMeasuredExtremes(void);
85 float accGetMeasuredMaxG(void);
86 void updateAccExtremes(void);
87 void accGetVibrationLevels(fpVector3_t *accVibeLevels);
88 float accGetVibrationLevel(void);
89 uint32_t accGetClipCount(void);
90 bool accIsClipped(void);
91 void accUpdate(void);
92 void accSetCalibrationValues(void);
93 void accInitFilters(void);
94 bool accIsHealthy(void);
95 bool accGetCalibrationAxisStatus(int axis);
96 uint8_t accGetCalibrationAxisFlags(void);