1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 22:35:23 +03:00

Fix Configurator Pid Controller Reset // Fix luxfloat no filter bug // Defaults for Version 2.9.0

This commit is contained in:
borisbstyle 2016-06-26 00:29:32 +02:00
parent f70f2960a8
commit 3d9b180b33
5 changed files with 10 additions and 45 deletions

View file

@ -154,7 +154,7 @@ static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
accelerometerTrims->values.yaw = 0; accelerometerTrims->values.yaw = 0;
} }
static void resetPidProfile(pidProfile_t *pidProfile) void resetPidProfile(pidProfile_t *pidProfile)
{ {
#if (defined(STM32F10X)) #if (defined(STM32F10X))
@ -169,7 +169,7 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->P8[PITCH] = 50; pidProfile->P8[PITCH] = 50;
pidProfile->I8[PITCH] = 40; pidProfile->I8[PITCH] = 40;
pidProfile->D8[PITCH] = 18; pidProfile->D8[PITCH] = 18;
pidProfile->P8[YAW] = 90; pidProfile->P8[YAW] = 80;
pidProfile->I8[YAW] = 45; pidProfile->I8[YAW] = 45;
pidProfile->D8[YAW] = 20; pidProfile->D8[YAW] = 20;
pidProfile->P8[PIDALT] = 50; pidProfile->P8[PIDALT] = 50;
@ -194,10 +194,10 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX; pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
pidProfile->yaw_lpf_hz = 80; pidProfile->yaw_lpf_hz = 80;
pidProfile->rollPitchItermIgnoreRate = 200; pidProfile->rollPitchItermIgnoreRate = 180;
pidProfile->yawItermIgnoreRate = 35; pidProfile->yawItermIgnoreRate = 35;
pidProfile->dterm_lpf_hz = 50; // filtering ON by default pidProfile->dterm_lpf_hz = 100; // filtering ON by default
pidProfile->deltaMethod = DELTA_FROM_ERROR; pidProfile->deltaMethod = DELTA_FROM_MEASUREMENT;
pidProfile->dynamic_pid = 1; pidProfile->dynamic_pid = 1;
#ifdef GTUNE #ifdef GTUNE

View file

@ -1500,7 +1500,7 @@ static bool processInCommand(void)
break; break;
case MSP_SET_RESET_CURR_PID: case MSP_SET_RESET_CURR_PID:
//resetPidProfile(&currentProfile->pidProfile); resetPidProfile(&currentProfile->pidProfile);
break; break;
case MSP_SET_SENSOR_ALIGNMENT: case MSP_SET_SENSOR_ALIGNMENT:

View file

@ -166,6 +166,8 @@ void gyroUpdate(void)
gyroADCf[axis] = applyBiQuadFilter((float) gyroADC[axis], &gyroFilterState[axis]); gyroADCf[axis] = applyBiQuadFilter((float) gyroADC[axis], &gyroFilterState[axis]);
gyroADC[axis] = lrintf(gyroADCf[axis]); gyroADC[axis] = lrintf(gyroADCf[axis]);
} }
} else {
gyroADCf[axis] = gyroADC[axis]; // Otherwise float pid controller will not have gyro input when filter disabled
} }
} }
} }

View file

@ -16,8 +16,8 @@
*/ */
#define FC_VERSION_MAJOR 2 // increment when a major release is made (big new feature, etc) #define FC_VERSION_MAJOR 2 // increment when a major release is made (big new feature, etc)
#define FC_VERSION_MINOR 8 // increment when a minor release is made (small new feature, change etc) #define FC_VERSION_MINOR 9 // increment when a minor release is made (small new feature, change etc)
#define FC_VERSION_PATCH_LEVEL 2 // increment when a bug is fixed #define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed
#define STR_HELPER(x) #x #define STR_HELPER(x) #x
#define STR(x) STR_HELPER(x) #define STR(x) STR_HELPER(x)

View file

@ -1,37 +0,0 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#define FC_VERSION_MAJOR 2 // increment when a major release is made (big new feature, etc)
#define FC_VERSION_MINOR 3 // increment when a minor release is made (small new feature, change etc)
#define FC_VERSION_PATCH_LEVEL 5 // increment when a bug is fixed
#define STR_HELPER(x) #x
#define STR(x) STR_HELPER(x)
#define FC_VERSION_STRING STR(FC_VERSION_MAJOR) "." STR(FC_VERSION_MINOR) "." STR(FC_VERSION_PATCH_LEVEL)
#define MW_VERSION 231
extern const char* const targetName;
#define GIT_SHORT_REVISION_LENGTH 7 // lower case hexadecimal digits.
extern const char* const shortGitRevision;
#define BUILD_DATE_LENGTH 11
extern const char* const buildDate; // "MMM DD YYYY" MMM = Jan/Feb/...
#define BUILD_TIME_LENGTH 8
extern const char* const buildTime; // "HH:MM:SS"