1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-21 15:25:36 +03:00

Moved targetLooptime into gyro_t, tidied gyro_sync and gyro

This commit is contained in:
Martin Budden 2016-06-26 08:41:24 +01:00
parent 19b02db8dd
commit 4d238b27d5
24 changed files with 52 additions and 72 deletions

View file

@ -29,7 +29,6 @@
#include "common/filter.h"
#include "drivers/sensor.h"
#include "drivers/gyro_sync.h"
#include "drivers/accgyro.h"
#include "sensors/sensors.h"
@ -74,7 +73,7 @@ pidControllerFuncPtr pid_controller = pidInteger; // which pid controller are we
void setTargetPidLooptime(uint8_t pidProcessDenom)
{
targetPidLooptime = targetLooptime * pidProcessDenom;
targetPidLooptime = gyro.targetLooptime * pidProcessDenom;
}
uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile, int32_t angleRate)