Merge pull request #11297 from SteveCEvans/baro_state
[betaflight.git] / src / main / sensors / acceleration.c
blob6e056be7a9de4e8065bd86ef0220b7ed1f8dfdf7
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 #include <stdbool.h>
22 #include <stdint.h>
24 #include "platform.h"
26 #ifdef USE_ACC
28 #include "build/debug.h"
30 #include "common/axis.h"
31 #include "common/filter.h"
32 #include "common/utils.h"
34 #include "config/feature.h"
36 #include "sensors/acceleration_init.h"
37 #include "sensors/boardalignment.h"
39 #include "acceleration.h"
41 FAST_DATA_ZERO_INIT acc_t acc; // acc access functions
43 static void applyAccelerationTrims(const flightDynamicsTrims_t *accelerationTrims)
45 acc.accADC[X] -= accelerationTrims->raw[X];
46 acc.accADC[Y] -= accelerationTrims->raw[Y];
47 acc.accADC[Z] -= accelerationTrims->raw[Z];
50 void accUpdate(timeUs_t currentTimeUs, rollAndPitchTrims_t *rollAndPitchTrims)
52 UNUSED(currentTimeUs);
54 if (!acc.dev.readFn(&acc.dev)) {
55 return;
57 acc.isAccelUpdatedAtLeastOnce = true;
59 for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
60 DEBUG_SET(DEBUG_ACCELEROMETER, axis, acc.dev.ADCRaw[axis]);
61 acc.accADC[axis] = acc.dev.ADCRaw[axis];
64 if (accelerationRuntime.accLpfCutHz) {
65 for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
66 acc.accADC[axis] = biquadFilterApply(&accelerationRuntime.accFilter[axis], acc.accADC[axis]);
70 if (acc.dev.accAlign == ALIGN_CUSTOM) {
71 alignSensorViaMatrix(acc.accADC, &acc.dev.rotationMatrix);
72 } else {
73 alignSensorViaRotation(acc.accADC, acc.dev.accAlign);
76 if (!accIsCalibrationComplete()) {
77 performAcclerationCalibration(rollAndPitchTrims);
80 if (featureIsEnabled(FEATURE_INFLIGHT_ACC_CAL)) {
81 performInflightAccelerationCalibration(rollAndPitchTrims);
84 applyAccelerationTrims(accelerationRuntime.accelerationTrims);
86 ++accelerationRuntime.accumulatedMeasurementCount;
87 for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
88 accelerationRuntime.accumulatedMeasurements[axis] += acc.accADC[axis];
92 bool accGetAccumulationAverage(float *accumulationAverage)
94 if (accelerationRuntime.accumulatedMeasurementCount > 0) {
95 // If we have gyro data accumulated, calculate average rate that will yield the same rotation
96 for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
97 accumulationAverage[axis] = accelerationRuntime.accumulatedMeasurements[axis] / accelerationRuntime.accumulatedMeasurementCount;
98 accelerationRuntime.accumulatedMeasurements[axis] = 0.0f;
100 accelerationRuntime.accumulatedMeasurementCount = 0;
101 return true;
102 } else {
103 for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
104 accumulationAverage[axis] = 0.0f;
106 return false;
110 #endif