1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-26 01:35:41 +03:00

Cleanup mw.c // Remove unnecessary functions

This commit is contained in:
borisbstyle 2016-12-18 01:28:20 +01:00
parent 979096f333
commit 4e3704374a
17 changed files with 46 additions and 348 deletions

View file

@ -74,20 +74,12 @@ typedef struct pidProfile_s {
uint8_t pidAtMinThrottle; // Disable/Enable pids on zero throttle. Normally even without airmode P and D would be active.
// Betaflight PID controller parameters
uint8_t itermThrottleGain; // Throttle coupling to iterm. Quick throttle changes will bump iterm
uint16_t itermThrottleThreshold; // max allowed throttle delta before errorGyroReset in ms
uint8_t setpointRelaxRatio; // Setpoint weight relaxation effect
uint8_t dtermSetpointWeight; // Setpoint weight for Dterm (0= measurement, 1= full error, 1 > agressive derivative)
uint16_t yawRateAccelLimit; // yaw accel limiter for deg/sec/ms
uint16_t rateAccelLimit; // accel limiter roll/pitch deg/sec/ms
float levelSensitivity;
#ifdef GTUNE
uint8_t gtune_lolimP[3]; // [0..200] Lower limit of P during G tune
uint8_t gtune_hilimP[3]; // [0..200] Higher limit of P during G tune. 0 Disables tuning for that axis.
uint8_t gtune_pwr; // [0..10] Strength of adjustment
uint16_t gtune_settle_time; // [200..1000] Settle time in ms
uint8_t gtune_average_cycles; // [8..128] Number of looptime cycles used for gyro average calculation
#endif
} pidProfile_t;
typedef struct pidConfig_s {