Blackbox device type 'file' (SITL) considered working when file handler is available
[inav.git] / src / main / sensors / acceleration.h
bloba25063ec4fdf14f506de44854f31dbe0e909d6cc
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 15.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_LSM6DXX,
47 ACC_FAKE,
48 ACC_MAX = ACC_FAKE
49 } accelerationSensor_e;
51 typedef struct {
52 float min;
53 float max;
54 } acc_extremes_t;
56 typedef struct acc_s {
57 accDev_t dev;
58 uint32_t accTargetLooptime;
59 float accADCf[XYZ_AXIS_COUNT]; // acceleration in g
60 float accVibeSq[XYZ_AXIS_COUNT];
61 float accVibe;
62 uint32_t accClipCount;
63 bool isClipped;
64 acc_extremes_t extremes[XYZ_AXIS_COUNT];
65 float maxG;
66 } acc_t;
68 extern acc_t acc;
70 typedef struct accelerometerConfig_s {
71 uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
72 uint16_t acc_lpf_hz; // cutoff frequency for the low pass filter used on the acc z-axis for althold in Hz
73 flightDynamicsTrims_t accZero; // Accelerometer offset
74 flightDynamicsTrims_t accGain; // Accelerometer gain to read exactly 1G
75 uint8_t acc_notch_hz; // Accelerometer notch filter frequency
76 uint8_t acc_notch_cutoff; // Accelerometer notch filter cutoff frequency
77 uint8_t acc_soft_lpf_type; // Accelerometer LPF type
78 } accelerometerConfig_t;
80 PG_DECLARE(accelerometerConfig_t, accelerometerConfig);
82 bool accInit(uint32_t accTargetLooptime);
83 bool accIsCalibrationComplete(void);
84 void accStartCalibration(void);
85 void accGetMeasuredAcceleration(fpVector3_t *measuredAcc);
86 const acc_extremes_t* accGetMeasuredExtremes(void);
87 float accGetMeasuredMaxG(void);
88 void updateAccExtremes(void);
89 void resetGForceStats(void);
90 void accGetVibrationLevels(fpVector3_t *accVibeLevels);
91 float accGetVibrationLevel(void);
92 uint32_t accGetClipCount(void);
93 bool accIsClipped(void);
94 void accUpdate(void);
95 void accSetCalibrationValues(void);
96 void accInitFilters(void);
97 bool accIsHealthy(void);
98 bool accGetCalibrationAxisStatus(int axis);
99 uint8_t accGetCalibrationAxisFlags(void);