1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 16:55:36 +03:00
betaflight/src/main/sensors/acceleration.h
2017-01-22 22:42:45 +00:00

77 lines
2.4 KiB
C

/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "drivers/accgyro.h"
#include "sensors/sensors.h"
// Type of accelerometer used/detected
typedef enum {
ACC_DEFAULT,
ACC_NONE,
ACC_ADXL345,
ACC_MPU6050,
ACC_MMA8452,
ACC_BMA280,
ACC_LSM303DLHC,
ACC_MPU6000,
ACC_MPU6500,
ACC_ICM20689,
ACC_MPU9250,
ACC_ICM20608G,
ACC_ICM20602,
ACC_FAKE
} accelerationSensor_e;
typedef struct acc_s {
accDev_t dev;
uint32_t accSamplingInterval;
int32_t accSmooth[XYZ_AXIS_COUNT];
bool isAccelUpdatedAtLeastOnce;
} acc_t;
extern acc_t acc;
typedef struct rollAndPitchTrims_s {
int16_t roll;
int16_t pitch;
} rollAndPitchTrims_t_def;
typedef union rollAndPitchTrims_u {
int16_t raw[2];
rollAndPitchTrims_t_def values;
} rollAndPitchTrims_t;
typedef struct accelerometerConfig_s {
uint16_t acc_lpf_hz; // cutoff frequency for the low pass filter used on the acc z-axis for althold in Hz
sensor_align_e acc_align; // acc alignment
uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
flightDynamicsTrims_t accZero;
rollAndPitchTrims_t accelerometerTrims;
} accelerometerConfig_t;
bool accInit(const accelerometerConfig_t *accelerometerConfig, uint32_t gyroTargetLooptime);
bool isAccelerationCalibrationComplete(void);
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired);
void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims);
void accUpdate(rollAndPitchTrims_t *rollAndPitchTrims);
union flightDynamicsTrims_u;
void setAccelerationTrims(union flightDynamicsTrims_u *accelerationTrimsToUse);
void setAccelerationFilter(uint16_t initialAccLpfCutHz);