1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-20 14:55:21 +03:00

merge 3.1.7 defaults

This commit is contained in:
borisbstyle 2017-04-05 15:36:52 +02:00
parent 6899c66a05
commit 99c87ba2dc

View file

@ -75,10 +75,10 @@ void resetPidProfile(pidProfile_t *pidProfile)
RESET_CONFIG(const pidProfile_t, pidProfile,
.P8[ROLL] = 44,
.I8[ROLL] = 40,
.D8[ROLL] = 20,
.D8[ROLL] = 30,
.P8[PITCH] = 58,
.I8[PITCH] = 50,
.D8[PITCH] = 22,
.D8[PITCH] = 35,
.P8[YAW] = 70,
.I8[YAW] = 45,
.D8[YAW] = 20,
@ -114,8 +114,8 @@ void resetPidProfile(pidProfile_t *pidProfile)
.pidAtMinThrottle = PID_STABILISATION_ON,
.levelAngleLimit = 55,
.levelSensitivity = 55,
.setpointRelaxRatio = 20,
.dtermSetpointWeight = 100,
.setpointRelaxRatio = 100,
.dtermSetpointWeight = 60,
.yawRateAccelLimit = 10.0f,
.rateAccelLimit = 0.0f,
.itermThrottleThreshold = 350,