mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 22:35:23 +03:00
Delete autotune.
This commit is contained in:
parent
6e59eb235d
commit
d36da111b2
30 changed files with 8 additions and 743 deletions
|
@ -41,7 +41,6 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "flight/autotune.h"
|
||||
#include "flight/filter.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
|
@ -96,13 +95,6 @@ const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH };
|
|||
|
||||
static filterStatePt1_t PTermState[3], DTermState[3];
|
||||
|
||||
#ifdef AUTOTUNE
|
||||
bool shouldAutotune(void)
|
||||
{
|
||||
return ARMING_FLAG(ARMED) && FLIGHT_MODE(AUTOTUNE_MODE);
|
||||
}
|
||||
#endif
|
||||
|
||||
static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
||||
{
|
||||
|
@ -158,12 +150,6 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
+max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here
|
||||
#endif
|
||||
|
||||
#ifdef AUTOTUNE
|
||||
if (shouldAutotune()) {
|
||||
errorAngle = autotune(rcAliasToAngleIndexMap[axis], &inclination, errorAngle);
|
||||
}
|
||||
#endif
|
||||
|
||||
if (FLIGHT_MODE(ANGLE_MODE)) {
|
||||
// it's the ANGLE mode - control is angle based, so control loop is needed
|
||||
AngleRate = errorAngle * pidProfile->A_level;
|
||||
|
@ -259,12 +245,6 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
+max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis];
|
||||
#endif
|
||||
|
||||
#ifdef AUTOTUNE
|
||||
if (shouldAutotune()) {
|
||||
errorAngle = DEGREES_TO_DECIDEGREES(autotune(rcAliasToAngleIndexMap[axis], &inclination, DECIDEGREES_TO_DEGREES(errorAngle)));
|
||||
}
|
||||
#endif
|
||||
|
||||
PTermACC = errorAngle * pidProfile->P8[PIDLEVEL] / 100; // 32 bits is needed for calculation: errorAngle*P8[PIDLEVEL] could exceed 32768 16 bits is ok for result
|
||||
PTermACC = constrain(PTermACC, -pidProfile->D8[PIDLEVEL] * 5, +pidProfile->D8[PIDLEVEL] * 5);
|
||||
|
||||
|
@ -367,12 +347,6 @@ static void pidMultiWii23(pidProfile_t *pidProfile, controlRateConfig_t *control
|
|||
+max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis];
|
||||
#endif
|
||||
|
||||
#ifdef AUTOTUNE
|
||||
if (shouldAutotune()) {
|
||||
errorAngle = DEGREES_TO_DECIDEGREES(autotune(rcAliasToAngleIndexMap[axis], &inclination, DECIDEGREES_TO_DEGREES(errorAngle)));
|
||||
}
|
||||
#endif
|
||||
|
||||
errorAngleI[axis] = constrain(errorAngleI[axis] + errorAngle, -10000, +10000); // WindUp //16 bits is ok here
|
||||
|
||||
PTermACC = ((int32_t)errorAngle * pidProfile->P8[PIDLEVEL]) >> 7; // 32 bits is needed for calculation: errorAngle*P8 could exceed 32768 16 bits is ok for result
|
||||
|
@ -473,12 +447,6 @@ static void pidMultiWiiHybrid(pidProfile_t *pidProfile, controlRateConfig_t *con
|
|||
+max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis];
|
||||
#endif
|
||||
|
||||
#ifdef AUTOTUNE
|
||||
if (shouldAutotune()) {
|
||||
errorAngle = DEGREES_TO_DECIDEGREES(autotune(rcAliasToAngleIndexMap[axis], &inclination, DECIDEGREES_TO_DEGREES(errorAngle)));
|
||||
}
|
||||
#endif
|
||||
|
||||
PTermACC = errorAngle * pidProfile->P8[PIDLEVEL] / 100; // 32 bits is needed for calculation: errorAngle*P8[PIDLEVEL] could exceed 32768 16 bits is ok for result
|
||||
PTermACC = constrain(PTermACC, -pidProfile->D8[PIDLEVEL] * 5, +pidProfile->D8[PIDLEVEL] * 5);
|
||||
|
||||
|
@ -597,11 +565,6 @@ rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
|||
error = constrain(2.0f * rcCommandAxis, -((int) max_angle_inclination), +max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis];
|
||||
#endif
|
||||
|
||||
#ifdef AUTOTUNE
|
||||
if (shouldAutotune()) {
|
||||
error = DEGREES_TO_DECIDEGREES(autotune(rcAliasToAngleIndexMap[axis], &inclination, DECIDEGREES_TO_DEGREES(error)));
|
||||
}
|
||||
#endif
|
||||
PTermACC = error * (float)pidProfile->P8[PIDLEVEL] * 0.008f;
|
||||
float limitf = (float)pidProfile->D8[PIDLEVEL] * 5.0f;
|
||||
PTermACC = constrain(PTermACC, -limitf, +limitf);
|
||||
|
@ -754,12 +717,6 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat
|
|||
+max_angle_inclination) - inclination.raw[axis] + angleTrim->raw[axis]; // 16 bits is ok here
|
||||
#endif
|
||||
|
||||
#ifdef AUTOTUNE
|
||||
if (shouldAutotune()) {
|
||||
errorAngle = DEGREES_TO_DECIDEGREES(autotune(rcAliasToAngleIndexMap[axis], &inclination, DECIDEGREES_TO_DEGREES(errorAngle)));
|
||||
}
|
||||
#endif
|
||||
|
||||
if (!FLIGHT_MODE(ANGLE_MODE)) { //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID
|
||||
AngleRateTmp = ((int32_t)(rate + 27) * rcCommand[axis]) >> 4;
|
||||
if (FLIGHT_MODE(HORIZON_MODE)) {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue