mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 04:45:24 +03:00
Fixed tests.
This commit is contained in:
parent
53278c08f8
commit
1771ea687f
3 changed files with 23 additions and 20 deletions
|
@ -566,7 +566,6 @@ TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController0)
|
|||
pidProfile.pid[PID_YAW].P = 7;
|
||||
pidProfile.pid[PID_YAW].I = 17;
|
||||
pidProfile.pid[PID_YAW].D = 27;
|
||||
useAdjustmentConfig(&pidProfile);
|
||||
// and
|
||||
controlRateConfig_t controlRateConfig;
|
||||
memset(&controlRateConfig, 0, sizeof (controlRateConfig));
|
||||
|
@ -602,7 +601,8 @@ TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController0)
|
|||
(1 << 5);
|
||||
|
||||
// when
|
||||
useRcControlsConfig(&pidProfile);
|
||||
currentPidProfile = &pidProfile;
|
||||
rcControlsInit();
|
||||
processRcAdjustments(&controlRateConfig);
|
||||
|
||||
// then
|
||||
|
@ -638,7 +638,6 @@ TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController2)
|
|||
pidProfile.D_f[PIDPITCH] = 20.0f;
|
||||
pidProfile.D_f[PIDROLL] = 25.0f;
|
||||
pidProfile.D_f[PIDYAW] = 27.0f;
|
||||
useAdjustmentConfig(&pidProfile);
|
||||
|
||||
// and
|
||||
controlRateConfig_t controlRateConfig;
|
||||
|
@ -675,7 +674,8 @@ TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController2)
|
|||
(1 << 5);
|
||||
|
||||
// when
|
||||
useRcControlsConfig(&escAndServoConfig, &pidProfile);
|
||||
currentPidProfile = &pidProfile;
|
||||
rcControlsInit();
|
||||
processRcAdjustments(&controlRateConfig, &rxConfig);
|
||||
|
||||
// then
|
||||
|
@ -733,6 +733,7 @@ uint16_t flightModeFlags = 0;
|
|||
int16_t heading;
|
||||
uint8_t stateFlags = 0;
|
||||
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
||||
pidProfile_t *currentPidProfile;
|
||||
rxRuntimeConfig_t rxRuntimeConfig;
|
||||
PG_REGISTER(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 0);
|
||||
PG_REGISTER(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 2);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue