Moved 'config.[ch]' into the 'config/' directory.
[betaflight.git] / src / test / unit / rc_controls_unittest.cc
blob248ecc430ddb9b04d24ca732ccab58ffb7a601df
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
17 #include <stdint.h>
19 #include <limits.h>
21 //#define DEBUG_RC_CONTROLS
23 extern "C" {
24 #include "platform.h"
26 #include "common/maths.h"
27 #include "common/axis.h"
28 #include "common/bitarray.h"
30 #include "pg/pg.h"
31 #include "pg/pg_ids.h"
32 #include "pg/rx.h"
34 #include "blackbox/blackbox.h"
35 #include "blackbox/blackbox_fielddefs.h"
37 #include "drivers/sensor.h"
39 #include "sensors/sensors.h"
40 #include "sensors/acceleration.h"
42 #include "io/beeper.h"
44 #include "rx/rx.h"
46 #include "flight/pid.h"
48 #include "config/config.h"
49 #include "fc/controlrate_profile.h"
50 #include "fc/rc_modes.h"
51 #include "fc/rc_adjustments.h"
53 #include "fc/rc_controls.h"
54 #include "fc/runtime_config.h"
55 #include "fc/core.h"
57 #include "scheduler/scheduler.h"
60 #include "unittest_macros.h"
61 #include "gtest/gtest.h"
63 void unsetArmingDisabled(armingDisableFlags_e flag) {
64 UNUSED(flag);
67 class RcControlsModesTest : public ::testing::Test {
68 protected:
69 virtual void SetUp() {
73 TEST_F(RcControlsModesTest, updateActivatedModesWithAllInputsAtMidde)
75 // given
76 boxBitmask_t mask;
77 memset(&mask, 0, sizeof(mask));
78 rcModeUpdate(&mask);
80 // and
81 memset(&rxRuntimeState, 0, sizeof(rxRuntimeState_t));
82 rxRuntimeState.channelCount = MAX_SUPPORTED_RC_CHANNEL_COUNT - NON_AUX_CHANNEL_COUNT;
84 // and
85 for (int index = AUX1; index < MAX_SUPPORTED_RC_CHANNEL_COUNT; index++) {
86 rcData[index] = PWM_RANGE_MIDDLE;
89 // when
90 analyzeModeActivationConditions();
91 updateActivatedModes();
93 // then
94 for (int index = 0; index < CHECKBOX_ITEM_COUNT; index++) {
95 #ifdef DEBUG_RC_CONTROLS
96 printf("iteration: %d\n", index);
97 #endif
98 EXPECT_EQ(false, IS_RC_MODE_ACTIVE((boxId_e)index));
102 TEST_F(RcControlsModesTest, updateActivatedModesUsingValidAuxConfigurationAndRXValues)
104 // given
105 modeActivationConditionsMutable(0)->modeId = (boxId_e)0;
106 modeActivationConditionsMutable(0)->auxChannelIndex = AUX1 - NON_AUX_CHANNEL_COUNT;
107 modeActivationConditionsMutable(0)->range.startStep = CHANNEL_VALUE_TO_STEP(1700);
108 modeActivationConditionsMutable(0)->range.endStep = CHANNEL_VALUE_TO_STEP(2100);
110 modeActivationConditionsMutable(1)->modeId = (boxId_e)1;
111 modeActivationConditionsMutable(1)->auxChannelIndex = AUX2 - NON_AUX_CHANNEL_COUNT;
112 modeActivationConditionsMutable(1)->range.startStep = CHANNEL_VALUE_TO_STEP(1300);
113 modeActivationConditionsMutable(1)->range.endStep = CHANNEL_VALUE_TO_STEP(1700);
115 modeActivationConditionsMutable(2)->modeId = (boxId_e)2;
116 modeActivationConditionsMutable(2)->auxChannelIndex = AUX3 - NON_AUX_CHANNEL_COUNT;
117 modeActivationConditionsMutable(2)->range.startStep = CHANNEL_VALUE_TO_STEP(900);
118 modeActivationConditionsMutable(2)->range.endStep = CHANNEL_VALUE_TO_STEP(1200);
120 modeActivationConditionsMutable(3)->modeId = (boxId_e)3;
121 modeActivationConditionsMutable(3)->auxChannelIndex = AUX4 - NON_AUX_CHANNEL_COUNT;
122 modeActivationConditionsMutable(3)->range.startStep = CHANNEL_VALUE_TO_STEP(900);
123 modeActivationConditionsMutable(3)->range.endStep = CHANNEL_VALUE_TO_STEP(2100);
125 modeActivationConditionsMutable(4)->modeId = (boxId_e)4;
126 modeActivationConditionsMutable(4)->auxChannelIndex = AUX5 - NON_AUX_CHANNEL_COUNT;
127 modeActivationConditionsMutable(4)->range.startStep = CHANNEL_VALUE_TO_STEP(900);
128 modeActivationConditionsMutable(4)->range.endStep = CHANNEL_VALUE_TO_STEP(925);
130 EXPECT_EQ(0, modeActivationConditions(4)->range.startStep);
131 EXPECT_EQ(1, modeActivationConditions(4)->range.endStep);
133 modeActivationConditionsMutable(5)->modeId = (boxId_e)5;
134 modeActivationConditionsMutable(5)->auxChannelIndex = AUX6 - NON_AUX_CHANNEL_COUNT;
135 modeActivationConditionsMutable(5)->range.startStep = CHANNEL_VALUE_TO_STEP(2075);
136 modeActivationConditionsMutable(5)->range.endStep = CHANNEL_VALUE_TO_STEP(2100);
138 EXPECT_EQ(47, modeActivationConditions(5)->range.startStep);
139 EXPECT_EQ(48, modeActivationConditions(5)->range.endStep);
141 modeActivationConditionsMutable(6)->modeId = (boxId_e)6;
142 modeActivationConditionsMutable(6)->auxChannelIndex = AUX7 - NON_AUX_CHANNEL_COUNT;
143 modeActivationConditionsMutable(6)->range.startStep = CHANNEL_VALUE_TO_STEP(925);
144 modeActivationConditionsMutable(6)->range.endStep = CHANNEL_VALUE_TO_STEP(950);
146 EXPECT_EQ(1, modeActivationConditions(6)->range.startStep);
147 EXPECT_EQ(2, modeActivationConditions(6)->range.endStep);
149 // and
150 boxBitmask_t mask;
151 memset(&mask, 0, sizeof(mask));
152 rcModeUpdate(&mask);
154 // and
155 memset(&rxRuntimeState, 0, sizeof(rxRuntimeState_t));
156 rxRuntimeState.channelCount = MAX_SUPPORTED_RC_CHANNEL_COUNT - NON_AUX_CHANNEL_COUNT;
158 // and
159 for (int index = AUX1; index < MAX_SUPPORTED_RC_CHANNEL_COUNT; index++) {
160 rcData[index] = PWM_RANGE_MIDDLE;
163 rcData[AUX1] = PWM_RANGE_MAX;
164 rcData[AUX2] = PWM_RANGE_MIDDLE;
165 rcData[AUX3] = PWM_RANGE_MIN;
166 rcData[AUX4] = PWM_RANGE_MAX;
167 rcData[AUX5] = 899; // value lower that range minimum should be treated the same as the lowest range value
168 rcData[AUX6] = 2101; // value higher than the range maximum should be treated the same as the highest range value
169 rcData[AUX7] = 950; // value equal to range step upper boundary should not activate the mode
171 // and
172 boxBitmask_t activeBoxIds;
173 memset(&activeBoxIds, 0, sizeof(boxBitmask_t));
174 bitArraySet(&activeBoxIds, 0);
175 bitArraySet(&activeBoxIds, 1);
176 bitArraySet(&activeBoxIds, 2);
177 bitArraySet(&activeBoxIds, 3);
178 bitArraySet(&activeBoxIds, 4);
179 bitArraySet(&activeBoxIds, 5);
181 // when
182 analyzeModeActivationConditions();
183 updateActivatedModes();
185 // then
186 for (int index = 0; index < CHECKBOX_ITEM_COUNT; index++) {
187 #ifdef DEBUG_RC_CONTROLS
188 printf("iteration: %d, %d\n", index, (bool)(bitArrayGet(&activeBoxIds, index)));
189 #endif
190 EXPECT_EQ((bool)(bitArrayGet(&activeBoxIds, index)), IS_RC_MODE_ACTIVE((boxId_e)index));
194 enum {
195 COUNTER_QUEUE_CONFIRMATION_BEEP,
196 COUNTER_CHANGE_CONTROL_RATE_PROFILE
198 #define CALL_COUNT_ITEM_COUNT 2
200 static int callCounts[CALL_COUNT_ITEM_COUNT];
202 #define CALL_COUNTER(item) (callCounts[item])
204 extern "C" {
205 void beeperConfirmationBeeps(uint8_t) {
206 callCounts[COUNTER_QUEUE_CONFIRMATION_BEEP]++;
209 void beeper(beeperMode_e mode) {
210 UNUSED(mode);
213 void changeControlRateProfile(uint8_t) {
214 callCounts[COUNTER_CHANGE_CONTROL_RATE_PROFILE]++;
219 void resetCallCounters(void) {
220 memset(&callCounts, 0, sizeof(callCounts));
223 uint32_t fixedMillis;
225 extern "C" {
226 uint32_t millis(void) {
227 return fixedMillis;
230 uint32_t micros(void) {
231 return fixedMillis * 1000;
235 void resetMillis(void) {
236 fixedMillis = 0;
239 #define DEFAULT_MIN_CHECK 1100
240 #define DEFAULT_MAX_CHECK 1900
242 extern "C" {
243 PG_REGISTER(rxConfig_t, rxConfig, PG_RX_CONFIG, 0);
245 extern int stepwiseAdjustmentCount;
246 extern timedAdjustmentState_t stepwiseAdjustments[MAX_ADJUSTMENT_RANGE_COUNT];
248 extern int continuosAdjustmentCount;
249 extern continuosAdjustmentState_t continuosAdjustments[MAX_ADJUSTMENT_RANGE_COUNT];
252 class RcControlsAdjustmentsTest : public ::testing::Test {
253 protected:
254 controlRateConfig_t controlRateConfig = {
255 .rcRates[FD_ROLL] = 90,
256 .rcRates[FD_PITCH] = 90,
257 .rcExpo[FD_ROLL] = 0,
258 .rcExpo[FD_PITCH] = 0,
259 .thrMid8 = 0,
260 .thrExpo8 = 0,
261 .rates = {0, 0, 0},
262 .dynThrPID = 0,
263 .rcExpo[FD_YAW] = 0,
264 .tpa_breakpoint = 0
267 channelRange_t fullRange = {
268 .startStep = MIN_MODE_RANGE_STEP,
269 .endStep = MAX_MODE_RANGE_STEP
272 int adjustmentRangesIndex;
274 virtual void SetUp() {
275 PG_RESET(rxConfig);
276 rxConfigMutable()->mincheck = DEFAULT_MIN_CHECK;
277 rxConfigMutable()->maxcheck = DEFAULT_MAX_CHECK;
278 rxConfigMutable()->midrc = 1500;
280 controlRateConfig.rcRates[FD_ROLL] = 90;
281 controlRateConfig.rcRates[FD_PITCH] = 90;
282 controlRateConfig.rcExpo[FD_ROLL] = 0;
283 controlRateConfig.rcExpo[FD_PITCH] = 0;
284 controlRateConfig.thrMid8 = 0;
285 controlRateConfig.thrExpo8 = 0;
286 controlRateConfig.rcExpo[FD_YAW] = 0;
287 controlRateConfig.rates[0] = 0;
288 controlRateConfig.rates[1] = 0;
289 controlRateConfig.rates[2] = 0;
290 controlRateConfig.dynThrPID = 0;
291 controlRateConfig.tpa_breakpoint = 0;
293 PG_RESET(adjustmentRanges);
294 adjustmentRangesIndex = 0;
296 stepwiseAdjustmentCount = 0;
297 continuosAdjustmentCount = 0;
300 int configureAdjustmentRange(uint8_t switchChannelIndex, uint8_t adjustmentConfigIndex) {
301 adjustmentRange_t *adjustmentRange = adjustmentRangesMutable(adjustmentRangesIndex);
302 adjustmentRange->auxChannelIndex = AUX1 - NON_AUX_CHANNEL_COUNT;
303 adjustmentRange->range = fullRange;
305 adjustmentRange->adjustmentConfig = adjustmentConfigIndex;
306 adjustmentRange->auxSwitchChannelIndex = switchChannelIndex;
308 return adjustmentRangesIndex++;
311 timedAdjustmentState_t *configureStepwiseAdjustment(uint8_t switchChannelIndex, uint8_t adjustmentConfigIndex) {
312 int adjustmentRangeIndex = configureAdjustmentRange(switchChannelIndex, adjustmentConfigIndex);
314 timedAdjustmentState_t *adjustmentState = &stepwiseAdjustments[stepwiseAdjustmentCount++];
315 adjustmentState->adjustmentRangeIndex = adjustmentRangeIndex;
316 adjustmentState->timeoutAt = 0;
317 adjustmentState->ready = true;
319 return adjustmentState;
322 void configureContinuosAdjustment(uint8_t switchChannelIndex, uint8_t adjustmentConfigIndex) {
323 int adjustmentRangeIndex = configureAdjustmentRange(switchChannelIndex, adjustmentConfigIndex);
325 continuosAdjustmentState_t *adjustmentState = &continuosAdjustments[continuosAdjustmentCount++];
326 adjustmentState->adjustmentRangeIndex = adjustmentRangeIndex;
327 adjustmentState->lastRcData = 0;
331 #define ADJUSTMENT_CONFIG_RATE_INDEX 1
333 TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsSticksInMiddle)
335 // given
336 const timedAdjustmentState_t *adjustmentState = configureStepwiseAdjustment(AUX3 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_CONFIG_RATE_INDEX);
338 // and
339 for (int index = AUX1; index < MAX_SUPPORTED_RC_CHANNEL_COUNT; index++) {
340 rcData[index] = PWM_RANGE_MIDDLE;
343 // and
344 resetCallCounters();
345 resetMillis();
347 // when
348 processRcAdjustments(&controlRateConfig);
350 // then
351 EXPECT_EQ(90, controlRateConfig.rcRates[FD_ROLL]);
352 EXPECT_EQ(90, controlRateConfig.rcRates[FD_PITCH]);
353 EXPECT_EQ(0, CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP));
354 EXPECT_EQ(true, adjustmentState->ready);
357 TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp)
359 // given
360 controlRateConfig_t controlRateConfig = {
361 .rcRates[FD_ROLL] = 90,
362 .rcRates[FD_PITCH] = 90,
363 .rcExpo[FD_ROLL] = 0,
364 .rcExpo[FD_PITCH] = 0,
365 .thrMid8 = 0,
366 .thrExpo8 = 0,
367 .rates = {0,0,0},
368 .dynThrPID = 0,
369 .rcExpo[FD_YAW] = 0,
370 .tpa_breakpoint = 0
373 // and
374 PG_RESET(rxConfig);
375 rxConfigMutable()->mincheck = DEFAULT_MIN_CHECK;
376 rxConfigMutable()->maxcheck = DEFAULT_MAX_CHECK;
377 rxConfigMutable()->midrc = 1500;
379 // and
380 const timedAdjustmentState_t *adjustmentState = configureStepwiseAdjustment(AUX3 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_CONFIG_RATE_INDEX);
382 // and
383 for (int index = AUX1; index < MAX_SUPPORTED_RC_CHANNEL_COUNT; index++) {
384 rcData[index] = PWM_RANGE_MIDDLE;
387 // and
388 resetCallCounters();
389 resetMillis();
391 // and
392 rcData[AUX3] = PWM_RANGE_MAX;
394 // and
395 fixedMillis = 496;
397 // when
398 processRcAdjustments(&controlRateConfig);
400 // then
401 EXPECT_EQ(91, controlRateConfig.rcRates[FD_ROLL]);
402 EXPECT_EQ(91, controlRateConfig.rcRates[FD_PITCH]);
403 EXPECT_EQ(1, CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP));
404 EXPECT_EQ(false, adjustmentState->ready);
407 // now pretend a short amount of time has passed, but not enough time to allow the value to have been increased
410 // given
411 fixedMillis = 497;
413 // when
414 processRcAdjustments(&controlRateConfig);
416 EXPECT_EQ(91, controlRateConfig.rcRates[FD_ROLL]);
417 EXPECT_EQ(91, controlRateConfig.rcRates[FD_PITCH]);
418 EXPECT_EQ(false, adjustmentState->ready);
422 // moving the switch back to the middle should immediately reset the state flag without increasing the value
426 // given
427 rcData[AUX3] = PWM_RANGE_MIDDLE;
429 // and
430 fixedMillis = 498;
432 // when
433 processRcAdjustments(&controlRateConfig);
435 EXPECT_EQ(91, controlRateConfig.rcRates[FD_ROLL]);
436 EXPECT_EQ(91, controlRateConfig.rcRates[FD_PITCH]);
437 EXPECT_EQ(true, adjustmentState->ready);
441 // flipping the switch again, before the state reset would have occurred, allows the value to be increased again
443 // given
444 rcData[AUX3] = PWM_RANGE_MAX;
446 // and
447 fixedMillis = 499;
449 // when
450 processRcAdjustments(&controlRateConfig);
452 // then
453 EXPECT_EQ(92, controlRateConfig.rcRates[FD_ROLL]);
454 EXPECT_EQ(92, controlRateConfig.rcRates[FD_PITCH]);
455 EXPECT_EQ(2, CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP));
456 EXPECT_EQ(false, adjustmentState->ready);
459 // leaving the switch up, after the original timer would have reset the state should now NOT cause
460 // the rate to increase, it should only increase after another 500ms from when the state was reset.
463 // given
464 fixedMillis = 500;
466 // when
467 processRcAdjustments(&controlRateConfig);
469 // then
470 EXPECT_EQ(92, controlRateConfig.rcRates[FD_ROLL]);
471 EXPECT_EQ(92, controlRateConfig.rcRates[FD_PITCH]);
472 EXPECT_EQ(false, adjustmentState->ready);
475 // should still not be able to be increased
478 // given
479 fixedMillis = 997;
481 // when
482 processRcAdjustments(&controlRateConfig);
484 // then
485 EXPECT_EQ(92, controlRateConfig.rcRates[FD_ROLL]);
486 EXPECT_EQ(92, controlRateConfig.rcRates[FD_PITCH]);
487 EXPECT_EQ(false, adjustmentState->ready);
490 // 500ms has now passed since the switch was returned to the middle, now that
491 // switch is still in the UP position after the timer has elapses it should
492 // be increased again.
495 // given
496 fixedMillis = 998;
498 // when
499 processRcAdjustments(&controlRateConfig);
501 // then
502 EXPECT_EQ(93, controlRateConfig.rcRates[FD_ROLL]);
503 EXPECT_EQ(93, controlRateConfig.rcRates[FD_PITCH]);
504 EXPECT_EQ(3, CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP));
505 EXPECT_EQ(false, adjustmentState->ready);
508 #define ADJUSTMENT_RATE_PROFILE_INDEX 12
510 TEST_F(RcControlsAdjustmentsTest, processRcRateProfileAdjustments)
512 // given
513 configureContinuosAdjustment(AUX4 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_RATE_PROFILE_INDEX);
515 // and
516 for (int index = AUX1; index < MAX_SUPPORTED_RC_CHANNEL_COUNT; index++) {
517 rcData[index] = PWM_RANGE_MIDDLE;
520 // and
521 resetCallCounters();
522 resetMillis();
524 // and
525 rcData[AUX4] = PWM_RANGE_MAX;
527 // when
528 processRcAdjustments(&controlRateConfig);
530 // then
531 EXPECT_EQ(1, CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP));
532 EXPECT_EQ(1, CALL_COUNTER(COUNTER_CHANGE_CONTROL_RATE_PROFILE));
535 #define ADJUSTMENT_PITCH_ROLL_P_INDEX 6
536 #define ADJUSTMENT_PITCH_ROLL_I_INDEX 7
537 #define ADJUSTMENT_PITCH_ROLL_D_INDEX 8
538 #define ADJUSTMENT_YAW_P_INDEX 9
539 #define ADJUSTMENT_YAW_I_INDEX 10
540 #define ADJUSTMENT_YAW_D_INDEX 11
542 TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController0)
544 // given
545 pidProfile_t pidProfile;
546 memset(&pidProfile, 0, sizeof (pidProfile));
547 pidProfile.pid[PID_PITCH].P = 0;
548 pidProfile.pid[PID_PITCH].I = 10;
549 pidProfile.pid[PID_PITCH].D = 20;
550 pidProfile.pid[PID_ROLL].P = 5;
551 pidProfile.pid[PID_ROLL].I = 15;
552 pidProfile.pid[PID_ROLL].D = 25;
553 pidProfile.pid[PID_YAW].P = 7;
554 pidProfile.pid[PID_YAW].I = 17;
555 pidProfile.pid[PID_YAW].D = 27;
556 // and
557 controlRateConfig_t controlRateConfig;
558 memset(&controlRateConfig, 0, sizeof (controlRateConfig));
560 const timedAdjustmentState_t *adjustmentState1 = configureStepwiseAdjustment(AUX1 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_PITCH_ROLL_P_INDEX);
561 const timedAdjustmentState_t *adjustmentState2 = configureStepwiseAdjustment(AUX2 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_PITCH_ROLL_I_INDEX);
562 const timedAdjustmentState_t *adjustmentState3 = configureStepwiseAdjustment(AUX3 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_PITCH_ROLL_D_INDEX);
563 const timedAdjustmentState_t *adjustmentState4 = configureStepwiseAdjustment(AUX1 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_YAW_P_INDEX);
564 const timedAdjustmentState_t *adjustmentState5 = configureStepwiseAdjustment(AUX2 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_YAW_I_INDEX);
565 const timedAdjustmentState_t *adjustmentState6 = configureStepwiseAdjustment(AUX3 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_YAW_D_INDEX);
567 // and
568 for (int index = AUX1; index < MAX_SUPPORTED_RC_CHANNEL_COUNT; index++) {
569 rcData[index] = PWM_RANGE_MIDDLE;
572 // and
573 resetCallCounters();
574 resetMillis();
576 // and
577 rcData[AUX1] = PWM_RANGE_MAX;
578 rcData[AUX2] = PWM_RANGE_MAX;
579 rcData[AUX3] = PWM_RANGE_MAX;
581 // when
582 currentPidProfile = &pidProfile;
583 rcControlsInit();
584 processRcAdjustments(&controlRateConfig);
586 // then
587 EXPECT_EQ(6, CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP));
588 EXPECT_EQ(false, adjustmentState1->ready);
589 EXPECT_EQ(false, adjustmentState2->ready);
590 EXPECT_EQ(false, adjustmentState3->ready);
591 EXPECT_EQ(false, adjustmentState4->ready);
592 EXPECT_EQ(false, adjustmentState5->ready);
593 EXPECT_EQ(false, adjustmentState6->ready);
595 // and
596 EXPECT_EQ(1, pidProfile.pid[PID_PITCH].P);
597 EXPECT_EQ(11, pidProfile.pid[PID_PITCH].I);
598 EXPECT_EQ(21, pidProfile.pid[PID_PITCH].D);
599 EXPECT_EQ(6, pidProfile.pid[PID_ROLL].P);
600 EXPECT_EQ(16, pidProfile.pid[PID_ROLL].I);
601 EXPECT_EQ(26, pidProfile.pid[PID_ROLL].D);
602 EXPECT_EQ(8, pidProfile.pid[PID_YAW].P);
603 EXPECT_EQ(18, pidProfile.pid[PID_YAW].I);
604 EXPECT_EQ(28, pidProfile.pid[PID_YAW].D);
607 extern "C" {
608 void setConfigDirty(void) {}
609 void saveConfigAndNotify(void) {}
610 void initRcProcessing(void) {}
611 void changePidProfile(uint8_t) {}
612 void pidInitConfig(const pidProfile_t *) {}
613 void accSetCalibrationCycles(uint16_t) {}
614 void gyroStartCalibration(bool isFirstArmingCalibration)
616 UNUSED(isFirstArmingCalibration);
618 void applyAccelerometerTrimsDelta(rollAndPitchTrims_t*) {}
619 void handleInflightCalibrationStickPosition(void) {}
620 bool featureIsEnabled(uint32_t) { return false;}
621 bool sensors(uint32_t) { return false;}
622 void tryArm(void) {}
623 void disarm(void) {}
624 void dashboardDisablePageCycling() {}
625 void dashboardEnablePageCycling() {}
627 bool failsafeIsActive() { return false; }
628 bool rxIsReceivingSignal() { return true; }
630 uint8_t getCurrentControlRateProfileIndex(void) {
631 return 0;
633 void GPS_reset_home_position(void) {}
634 void baroSetCalibrationCycles(uint16_t) {}
636 void blackboxLogEvent(FlightLogEvent, flightLogEventData_t *) {}
638 bool cmsInMenu = false;
639 uint8_t armingFlags = 0;
640 uint16_t flightModeFlags = 0;
641 int16_t heading;
642 uint8_t stateFlags = 0;
643 int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
644 pidProfile_t *currentPidProfile;
645 rxRuntimeState_t rxRuntimeState;
646 PG_REGISTER(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 0);
647 PG_REGISTER(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 2);
648 void resetArmingDisabled(void) {}
649 timeDelta_t getTaskDeltaTime(cfTaskId_e) { return 20000; }
650 armingDisableFlags_e getArmingDisableFlags(void) {
651 return (armingDisableFlags_e) 0;
653 bool isTryingToArm(void) { return false; }
654 void resetTryingToArm(void) {}
655 void setLedProfile(uint8_t profile) { UNUSED(profile); }
656 uint8_t getLedProfile(void) { return 0; }