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

@ -168,8 +168,8 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
pidProfile->pidSumLimit = PIDSUM_LIMIT;
pidProfile->yaw_lpf_hz = 0;
pidProfile->rollPitchItermIgnoreRate = 130;
pidProfile->yawItermIgnoreRate = 32;
pidProfile->rollPitchItermIgnoreRate = 200;
pidProfile->yawItermIgnoreRate = 55;
pidProfile->dterm_filter_type = FILTER_BIQUAD;
pidProfile->dterm_lpf_hz = 100; // filtering ON by default
pidProfile->dterm_notch_hz = 260;
@ -182,20 +182,8 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->dtermSetpointWeight = 200;
pidProfile->yawRateAccelLimit = 220;
pidProfile->rateAccelLimit = 0;
pidProfile->itermThrottleGain = 0;
pidProfile->itermThrottleThreshold = 350;
pidProfile->levelSensitivity = 2.0f;
#ifdef GTUNE
pidProfile->gtune_lolimP[ROLL] = 10; // [0..200] Lower limit of ROLL P during G tune.
pidProfile->gtune_lolimP[PITCH] = 10; // [0..200] Lower limit of PITCH P during G tune.
pidProfile->gtune_lolimP[YAW] = 10; // [0..200] Lower limit of YAW P during G tune.
pidProfile->gtune_hilimP[ROLL] = 100; // [0..200] Higher limit of ROLL P during G tune. 0 Disables tuning for that axis.
pidProfile->gtune_hilimP[PITCH] = 100; // [0..200] Higher limit of PITCH P during G tune. 0 Disables tuning for that axis.
pidProfile->gtune_hilimP[YAW] = 100; // [0..200] Higher limit of YAW P during G tune. 0 Disables tuning for that axis.
pidProfile->gtune_pwr = 0; // [0..10] Strength of adjustment
pidProfile->gtune_settle_time = 450; // [200..1000] Settle time in ms
pidProfile->gtune_average_cycles = 16; // [8..128] Number of looptime cycles used for gyro average calculation
#endif
}
void resetProfile(profile_t *profile)