mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 17:25:20 +03:00
Add acc and gyro accumulators to improve attitude estimation
This commit is contained in:
parent
d3d5b107cc
commit
22c672fa7d
9 changed files with 79 additions and 14 deletions
|
@ -18,6 +18,7 @@
|
|||
#pragma once
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/time.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/sensor.h"
|
||||
|
@ -69,7 +70,8 @@ PG_DECLARE(gyroConfig_t, gyroConfig);
|
|||
bool gyroInit(void);
|
||||
|
||||
void gyroInitFilters(void);
|
||||
void gyroUpdate(void);
|
||||
void gyroUpdate(timeUs_t currentTimeUs);
|
||||
bool gyroGetAccumulationAverage(float *accumulation);
|
||||
const busDevice_t *gyroSensorBus(void);
|
||||
struct mpuConfiguration_s;
|
||||
const struct mpuConfiguration_s *gyroMpuConfiguration(void);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue