1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-13 11:29:58 +03:00

Add acc and gyro accumulators to improve attitude estimation

This commit is contained in:
Martin Budden 2017-11-26 20:20:48 +00:00
parent d3d5b107cc
commit 22c672fa7d
9 changed files with 79 additions and 14 deletions

View file

@ -17,6 +17,7 @@
#pragma once
#include "common/time.h"
#include "config/parameter_group.h"
#include "drivers/accgyro/accgyro.h"
#include "sensors/sensors.h"
@ -77,7 +78,8 @@ bool accInit(uint32_t gyroTargetLooptime);
bool isAccelerationCalibrationComplete(void);
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired);
void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims);
void accUpdate(rollAndPitchTrims_t *rollAndPitchTrims);
void accUpdate(timeUs_t currentTimeUs, rollAndPitchTrims_t *rollAndPitchTrims);
bool accGetAccumulationAverage(float *accumulation);
union flightDynamicsTrims_u;
void setAccelerationTrims(union flightDynamicsTrims_u *accelerationTrimsToUse);
void accInitFilters(void);