mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 13:25:30 +03:00
Cleanup code // add unittestst for iterm windup
This commit is contained in:
parent
261f8d679a
commit
00dbaf9fa7
5 changed files with 32 additions and 21 deletions
|
@ -361,15 +361,6 @@ bool mixerIsTricopter(void)
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
bool mixerIsOutputSaturated(int axis, float errorRate)
|
|
||||||
{
|
|
||||||
if (axis == FD_YAW && mixerIsTricopter()) {
|
|
||||||
return mixerTricopterIsServoSaturated(errorRate);
|
|
||||||
}
|
|
||||||
|
|
||||||
return motorMixRange >= 1.0f;
|
|
||||||
}
|
|
||||||
|
|
||||||
// All PWM motor scaling is done to standard PWM range of 1000-2000 for easier tick conversion with legacy code / configurator
|
// All PWM motor scaling is done to standard PWM range of 1000-2000 for easier tick conversion with legacy code / configurator
|
||||||
// DSHOT scaling is done to the actual dshot range
|
// DSHOT scaling is done to the actual dshot range
|
||||||
void initEscEndpoints(void)
|
void initEscEndpoints(void)
|
||||||
|
|
|
@ -117,7 +117,6 @@ struct rxConfig_s;
|
||||||
uint8_t getMotorCount(void);
|
uint8_t getMotorCount(void);
|
||||||
float getMotorMixRange(void);
|
float getMotorMixRange(void);
|
||||||
bool areMotorsRunning(void);
|
bool areMotorsRunning(void);
|
||||||
bool mixerIsOutputSaturated(int axis, float errorRate);
|
|
||||||
|
|
||||||
void mixerLoadMix(int index, motorMixer_t *customMixers);
|
void mixerLoadMix(int index, motorMixer_t *customMixers);
|
||||||
void mixerInit(mixerMode_e mixerMode);
|
void mixerInit(mixerMode_e mixerMode);
|
||||||
|
|
|
@ -445,7 +445,7 @@ void pidInitConfig(const pidProfile_t *pidProfile)
|
||||||
horizonFactorRatio = (100 - pidProfile->horizon_tilt_effect) * 0.01f;
|
horizonFactorRatio = (100 - pidProfile->horizon_tilt_effect) * 0.01f;
|
||||||
maxVelocity[FD_ROLL] = maxVelocity[FD_PITCH] = pidProfile->rateAccelLimit * 100 * dT;
|
maxVelocity[FD_ROLL] = maxVelocity[FD_PITCH] = pidProfile->rateAccelLimit * 100 * dT;
|
||||||
maxVelocity[FD_YAW] = pidProfile->yawRateAccelLimit * 100 * dT;
|
maxVelocity[FD_YAW] = pidProfile->yawRateAccelLimit * 100 * dT;
|
||||||
const float ITermWindupPoint = (float)pidProfile->itermWindupPointPercent / 100.0f;
|
const float ITermWindupPoint = ((float)pidProfile->itermWindupPointPercent - 0.001f) / 100.0f;
|
||||||
ITermWindupPointInv = 1.0f / (1.0f - ITermWindupPoint);
|
ITermWindupPointInv = 1.0f / (1.0f - ITermWindupPoint);
|
||||||
itermAcceleratorGain = pidProfile->itermAcceleratorGain;
|
itermAcceleratorGain = pidProfile->itermAcceleratorGain;
|
||||||
crashTimeLimitUs = pidProfile->crash_time * 1000;
|
crashTimeLimitUs = pidProfile->crash_time * 1000;
|
||||||
|
@ -985,12 +985,7 @@ void FAST_CODE pidController(const pidProfile_t *pidProfile, const rollAndPitchT
|
||||||
}
|
}
|
||||||
|
|
||||||
// -----calculate I component
|
// -----calculate I component
|
||||||
const float ITermNew = constrainf(ITerm + pidCoefficient[axis].Ki * itermErrorRate * dynCi, -itermLimit, itermLimit);
|
pidData[axis].I = constrainf(ITerm + pidCoefficient[axis].Ki * itermErrorRate * dynCi, -itermLimit, itermLimit);
|
||||||
const bool outputSaturated = mixerIsOutputSaturated(axis, errorRate);
|
|
||||||
if (outputSaturated == false || ABS(ITermNew) < ABS(ITerm)) {
|
|
||||||
// Only increase ITerm if output is not saturated
|
|
||||||
pidData[axis].I = ITermNew;
|
|
||||||
}
|
|
||||||
|
|
||||||
// -----calculate D component
|
// -----calculate D component
|
||||||
if (pidCoefficient[axis].Kd > 0) {
|
if (pidCoefficient[axis].Kd > 0) {
|
||||||
|
|
|
@ -846,7 +846,7 @@ const clivalue_t valueTable[] = {
|
||||||
{ "iterm_relax_type", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ITERM_RELAX_TYPE }, PG_PID_PROFILE, offsetof(pidProfile_t, iterm_relax_type) },
|
{ "iterm_relax_type", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ITERM_RELAX_TYPE }, PG_PID_PROFILE, offsetof(pidProfile_t, iterm_relax_type) },
|
||||||
{ "iterm_relax_cutoff", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 1, 100 }, PG_PID_PROFILE, offsetof(pidProfile_t, iterm_relax_cutoff) },
|
{ "iterm_relax_cutoff", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 1, 100 }, PG_PID_PROFILE, offsetof(pidProfile_t, iterm_relax_cutoff) },
|
||||||
#endif
|
#endif
|
||||||
{ "iterm_windup", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 30, 99 }, PG_PID_PROFILE, offsetof(pidProfile_t, itermWindupPointPercent) },
|
{ "iterm_windup", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 30, 100 }, PG_PID_PROFILE, offsetof(pidProfile_t, itermWindupPointPercent) },
|
||||||
{ "iterm_limit", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 500 }, PG_PID_PROFILE, offsetof(pidProfile_t, itermLimit) },
|
{ "iterm_limit", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 500 }, PG_PID_PROFILE, offsetof(pidProfile_t, itermLimit) },
|
||||||
{ "pidsum_limit", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { PIDSUM_LIMIT_MIN, PIDSUM_LIMIT_MAX }, PG_PID_PROFILE, offsetof(pidProfile_t, pidSumLimit) },
|
{ "pidsum_limit", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { PIDSUM_LIMIT_MIN, PIDSUM_LIMIT_MAX }, PG_PID_PROFILE, offsetof(pidProfile_t, pidSumLimit) },
|
||||||
{ "pidsum_limit_yaw", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { PIDSUM_LIMIT_MIN, PIDSUM_LIMIT_MAX }, PG_PID_PROFILE, offsetof(pidProfile_t, pidSumLimitYaw) },
|
{ "pidsum_limit_yaw", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { PIDSUM_LIMIT_MIN, PIDSUM_LIMIT_MAX }, PG_PID_PROFILE, offsetof(pidProfile_t, pidSumLimitYaw) },
|
||||||
|
|
|
@ -67,7 +67,6 @@ extern "C" {
|
||||||
float getThrottlePIDAttenuation(void) { return simulatedThrottlePIDAttenuation; }
|
float getThrottlePIDAttenuation(void) { return simulatedThrottlePIDAttenuation; }
|
||||||
float getMotorMixRange(void) { return simulatedMotorMixRange; }
|
float getMotorMixRange(void) { return simulatedMotorMixRange; }
|
||||||
float getSetpointRate(int axis) { return simulatedSetpointRate[axis]; }
|
float getSetpointRate(int axis) { return simulatedSetpointRate[axis]; }
|
||||||
bool mixerIsOutputSaturated(int, float) { return simulateMixerSaturated; }
|
|
||||||
float getRcDeflectionAbs(int axis) { return ABS(simulatedRcDeflection[axis]); }
|
float getRcDeflectionAbs(int axis) { return ABS(simulatedRcDeflection[axis]); }
|
||||||
void systemBeep(bool) { }
|
void systemBeep(bool) { }
|
||||||
bool gyroOverflowDetected(void) { return false; }
|
bool gyroOverflowDetected(void) { return false; }
|
||||||
|
@ -431,14 +430,41 @@ TEST(pidControllerTest, testMixerSaturation) {
|
||||||
// Test full stick response
|
// Test full stick response
|
||||||
setStickPosition(FD_ROLL, 1.0f);
|
setStickPosition(FD_ROLL, 1.0f);
|
||||||
setStickPosition(FD_PITCH, -1.0f);
|
setStickPosition(FD_PITCH, -1.0f);
|
||||||
simulateMixerSaturated = true;
|
setStickPosition(FD_YAW, 1.0f);
|
||||||
|
simulatedMotorMixRange = 2.0f;
|
||||||
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
|
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
|
||||||
|
|
||||||
// Expect no iterm accumulation
|
// Expect no iterm accumulation
|
||||||
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].P);
|
|
||||||
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].I);
|
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].I);
|
||||||
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].I);
|
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].I);
|
||||||
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].I);
|
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].I);
|
||||||
|
|
||||||
|
// Test itermWindup limit
|
||||||
|
// First store values without exceeding iterm windup limit
|
||||||
|
resetTest();
|
||||||
|
ENABLE_ARMING_FLAG(ARMED);
|
||||||
|
pidStabilisationState(PID_STABILISATION_ON);
|
||||||
|
setStickPosition(FD_ROLL, 0.1f);
|
||||||
|
setStickPosition(FD_PITCH, -0.1f);
|
||||||
|
setStickPosition(FD_YAW, 0.1f);
|
||||||
|
simulatedMotorMixRange = 0.0f;
|
||||||
|
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
|
||||||
|
float rollTestIterm = pidData[FD_ROLL].I;
|
||||||
|
float pitchTestIterm = pidData[FD_PITCH].I;
|
||||||
|
float yawTestIterm = pidData[FD_YAW].I;
|
||||||
|
|
||||||
|
// Now compare values when exceeding the limit
|
||||||
|
resetTest();
|
||||||
|
ENABLE_ARMING_FLAG(ARMED);
|
||||||
|
pidStabilisationState(PID_STABILISATION_ON);
|
||||||
|
setStickPosition(FD_ROLL, 0.1f);
|
||||||
|
setStickPosition(FD_PITCH, -0.1f);
|
||||||
|
setStickPosition(FD_YAW, 0.1f);
|
||||||
|
simulatedMotorMixRange = (pidProfile->itermWindupPointPercent + 1 / 100.0f);
|
||||||
|
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
|
||||||
|
ASSERT_NE(pidData[FD_ROLL].I, rollTestIterm);
|
||||||
|
ASSERT_NE(pidData[FD_PITCH].I, pitchTestIterm);
|
||||||
|
ASSERT_NE(pidData[FD_YAW].I, yawTestIterm);
|
||||||
}
|
}
|
||||||
|
|
||||||
// TODO - Add more scenarios
|
// TODO - Add more scenarios
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue