mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-18 13:55:18 +03:00
Change default iterm_windup
This commit is contained in:
parent
00dbaf9fa7
commit
aa44fd6bbd
2 changed files with 16 additions and 9 deletions
|
@ -460,11 +460,11 @@ TEST(pidControllerTest, testMixerSaturation) {
|
|||
setStickPosition(FD_ROLL, 0.1f);
|
||||
setStickPosition(FD_PITCH, -0.1f);
|
||||
setStickPosition(FD_YAW, 0.1f);
|
||||
simulatedMotorMixRange = (pidProfile->itermWindupPointPercent + 1 / 100.0f);
|
||||
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);
|
||||
ASSERT_LT(pidData[FD_ROLL].I, rollTestIterm);
|
||||
ASSERT_GE(pidData[FD_PITCH].I, pitchTestIterm);
|
||||
ASSERT_LT(pidData[FD_YAW].I, yawTestIterm);
|
||||
}
|
||||
|
||||
// TODO - Add more scenarios
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue