mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 13:25:30 +03:00
Added new debug mode to time pidloop subtasks.
This commit is contained in:
parent
fa24d2950e
commit
825475fd43
10 changed files with 98 additions and 78 deletions
|
@ -62,9 +62,10 @@ int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3];
|
|||
uint8_t PIDweight[3];
|
||||
|
||||
static int32_t errorGyroI[3], errorGyroILimit[3];
|
||||
#ifndef SKIP_PID_LUXFLOAT
|
||||
static float errorGyroIf[3], errorGyroIfLimit[3];
|
||||
static int32_t errorAngleI[2];
|
||||
static float errorAngleIf[2];
|
||||
#endif
|
||||
|
||||
static bool lowThrottlePidReduction;
|
||||
|
||||
static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
|
||||
|
@ -103,22 +104,15 @@ uint16_t getDynamicKp(int axis, pidProfile_t *pidProfile) {
|
|||
return dynamicKp;
|
||||
}
|
||||
|
||||
void pidResetErrorAngle(void)
|
||||
{
|
||||
errorAngleI[ROLL] = 0;
|
||||
errorAngleI[PITCH] = 0;
|
||||
|
||||
errorAngleIf[ROLL] = 0.0f;
|
||||
errorAngleIf[PITCH] = 0.0f;
|
||||
}
|
||||
|
||||
void pidResetErrorGyroState(uint8_t resetOption)
|
||||
{
|
||||
if (resetOption >= RESET_ITERM) {
|
||||
int axis;
|
||||
for (axis = 0; axis < 3; axis++) {
|
||||
errorGyroI[axis] = 0;
|
||||
#ifndef SKIP_PID_LUXFLOAT
|
||||
errorGyroIf[axis] = 0.0f;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -141,6 +135,7 @@ const angle_index_t rcAliasToAngleIndexMap[] = { AI_ROLL, AI_PITCH };
|
|||
static filterStatePt1_t deltaFilterState[3];
|
||||
static filterStatePt1_t yawFilterState;
|
||||
|
||||
#ifndef SKIP_PID_LUXFLOAT
|
||||
static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig,
|
||||
uint16_t max_angle_inclination, rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
||||
{
|
||||
|
@ -280,6 +275,7 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
#endif
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
static void pidMultiWiiRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRateConfig, uint16_t max_angle_inclination,
|
||||
rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
||||
|
@ -426,8 +422,10 @@ void pidSetController(pidControllerType_e type)
|
|||
case PID_CONTROLLER_MWREWRITE:
|
||||
pid_controller = pidMultiWiiRewrite;
|
||||
break;
|
||||
#ifndef SKIP_PID_LUXFLOAT
|
||||
case PID_CONTROLLER_LUX_FLOAT:
|
||||
pid_controller = pidLuxFloat;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue