1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 06:15:16 +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

@ -40,7 +40,6 @@
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/gyro_sync.h"
#include "drivers/sdcard.h"
#include "drivers/buf_writer.h"
#include "drivers/max7456.h"
@ -109,8 +108,8 @@ void setGyroSamplingSpeed(uint16_t looptime) {
uint16_t gyroSampleRate = 1000;
uint8_t maxDivider = 1;
if (looptime != targetLooptime || looptime == 0) {
if (looptime == 0) looptime = targetLooptime; // needed for pid controller changes
if (looptime != gyro.targetLooptime || looptime == 0) {
if (looptime == 0) looptime = gyro.targetLooptime; // needed for pid controller changes
#ifdef STM32F303xC
if (looptime < 1000) {
masterConfig.gyro_lpf = 0;
@ -854,7 +853,7 @@ static bool processOutCommand(uint8_t cmdMSP)
break;
case MSP_LOOP_TIME:
headSerialReply(2);
serialize16((uint16_t)targetLooptime);
serialize16((uint16_t)gyro.targetLooptime);
break;
case MSP_RC_TUNING:
headSerialReply(11);