Update unit tests
[betaflight.git] / src / test / unit / link_quality_unittest.cc
blob26441c40bba50c241461f7f678cb8986bf4ac742
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/>.
18 #include <stdint.h>
19 #include <stdbool.h>
20 #include <stdio.h>
21 #include <string.h>
23 extern "C" {
24 #include "platform.h"
25 #include "build/debug.h"
27 #include "blackbox/blackbox.h"
28 #include "blackbox/blackbox_io.h"
30 #include "common/crc.h"
31 #include "common/printf.h"
32 #include "common/streambuf.h"
33 #include "common/time.h"
34 #include "common/utils.h"
36 #include "config/config.h"
38 #include "drivers/osd_symbols.h"
39 #include "drivers/persistent.h"
40 #include "drivers/serial.h"
41 #include "drivers/system.h"
43 #include "fc/core.h"
44 #include "fc/rc_controls.h"
45 #include "fc/rc_modes.h"
46 #include "fc/runtime_config.h"
48 #include "flight/imu.h"
49 #include "flight/mixer.h"
50 #include "flight/pid.h"
52 #include "io/beeper.h"
53 #include "io/gps.h"
54 #include "io/serial.h"
56 #include "osd/osd.h"
57 #include "osd/osd_elements.h"
58 #include "osd/osd_warnings.h"
60 #include "pg/pg.h"
61 #include "pg/pg_ids.h"
62 #include "pg/rx.h"
64 #include "rx/rx.h"
66 #include "sensors/battery.h"
68 attitudeEulerAngles_t attitude;
69 float rMat[3][3];
71 pidProfile_t *currentPidProfile;
72 float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
73 uint8_t GPS_numSat;
74 uint16_t GPS_distanceToHome;
75 int16_t GPS_directionToHome;
76 uint32_t GPS_distanceFlownInCm;
77 int32_t GPS_coord[2];
78 gpsSolutionData_t gpsSol;
79 float motor[8];
80 acc_t acc;
81 float accAverage[XYZ_AXIS_COUNT];
83 PG_REGISTER(batteryConfig_t, batteryConfig, PG_BATTERY_CONFIG, 0);
84 PG_REGISTER(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 0);
85 PG_REGISTER(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 0);
86 PG_REGISTER(pilotConfig_t, pilotConfig, PG_PILOT_CONFIG, 0);
87 PG_REGISTER(imuConfig_t, imuConfig, PG_IMU_CONFIG, 0);
88 PG_REGISTER(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 0);
90 timeUs_t simulationTime = 0;
92 void osdRefresh(timeUs_t currentTimeUs);
93 uint16_t updateLinkQualitySamples(uint16_t value);
94 #define LINK_QUALITY_SAMPLE_COUNT 16
97 /* #define DEBUG_OSD */
99 #include "unittest_macros.h"
100 #include "unittest_displayport.h"
101 #include "gtest/gtest.h"
103 extern "C" {
104 PG_REGISTER(flight3DConfig_t, flight3DConfig, PG_MOTOR_3D_CONFIG, 0);
106 boxBitmask_t rcModeActivationMask;
107 int16_t debug[DEBUG16_VALUE_COUNT];
108 uint8_t debugMode = 0;
110 uint16_t updateLinkQualitySamples(uint16_t value);
112 extern uint16_t applyRxChannelRangeConfiguraton(int sample, const rxChannelRangeConfig_t *range);
114 void setDefaultSimulationState()
117 setLinkQualityDirect(LINK_QUALITY_MAX_VALUE);
121 * Performs a test of the OSD actions on arming.
122 * (reused throughout the test suite)
124 void doTestArm(bool testEmpty = true)
126 // given
127 // craft has been armed
128 ENABLE_ARMING_FLAG(ARMED);
130 // when
131 // sufficient OSD updates have been called
132 osdRefresh(simulationTime);
134 // then
135 // arming alert displayed
136 displayPortTestBufferSubstring(12, 7, "ARMED");
138 // given
139 // armed alert times out (0.5 seconds)
140 simulationTime += 0.5e6;
142 // when
143 // sufficient OSD updates have been called
144 osdRefresh(simulationTime);
146 // then
147 // arming alert disappears
148 #ifdef DEBUG_OSD
149 displayPortTestPrint();
150 #endif
151 if (testEmpty) {
152 displayPortTestBufferIsEmpty();
157 * Auxiliary function. Test is there're stats that must be shown
159 bool isSomeStatEnabled(void) {
160 return (osdConfigMutable()->enabled_stats != 0);
164 * Performs a test of the OSD actions on disarming.
165 * (reused throughout the test suite)
167 void doTestDisarm()
169 // given
170 // craft is disarmed after having been armed
171 DISABLE_ARMING_FLAG(ARMED);
173 // when
174 // sufficient OSD updates have been called
175 osdRefresh(simulationTime);
177 // then
178 // post flight statistics displayed
179 if (isSomeStatEnabled()) {
180 displayPortTestBufferSubstring(2, 2, " --- STATS ---");
185 * Tests initialisation of the OSD and the power on splash screen.
187 TEST(LQTest, TestInit)
189 // given
190 // display port is initialised
191 displayPortTestInit();
193 // and
194 // default state values are set
195 setDefaultSimulationState();
197 // and
198 // this battery configuration (used for battery voltage elements)
199 batteryConfigMutable()->vbatmincellvoltage = 330;
200 batteryConfigMutable()->vbatmaxcellvoltage = 430;
202 // when
203 // OSD is initialised
204 osdInit(&testDisplayPort, OSD_DISPLAYPORT_DEVICE_AUTO);
206 // then
207 // display buffer should contain splash screen
208 displayPortTestBufferSubstring(7, 8, "MENU:THR MID");
209 displayPortTestBufferSubstring(11, 9, "+ YAW LEFT");
210 displayPortTestBufferSubstring(11, 10, "+ PITCH UP");
212 // when
213 // splash screen timeout has elapsed
214 simulationTime += 4e6;
215 osdUpdate(simulationTime);
217 // then
218 // display buffer should be empty
219 #ifdef DEBUG_OSD
220 displayPortTestPrint();
221 #endif
222 displayPortTestBufferIsEmpty();
225 * Tests the Tests the OSD_LINK_QUALITY element updateLinkQualitySamples default LQ_SOURCE_NONE
227 TEST(LQTest, TestElement_LQ_SOURCE_NONE_SAMPLES)
229 // given
232 linkQualitySource = LQ_SOURCE_NONE;
234 osdElementConfigMutable()->item_pos[OSD_LINK_QUALITY] = OSD_POS(8, 1) | OSD_PROFILE_1_FLAG;
235 osdConfigMutable()->link_quality_alarm = 0;
237 osdAnalyzeActiveElements();
239 // when samples populated 100%
240 for (int x = 0; x < LINK_QUALITY_SAMPLE_COUNT; x++) {
241 setLinkQualityDirect(updateLinkQualitySamples(LINK_QUALITY_MAX_VALUE));
245 displayClearScreen(&testDisplayPort);
246 osdRefresh(simulationTime);
248 // then
249 displayPortTestBufferSubstring(8, 1, "%c9", SYM_LINK_QUALITY);
251 // when updateLinkQualitySamples used 50% rounds to 4
252 for (int x = 0; x < LINK_QUALITY_SAMPLE_COUNT; x++) {
253 setLinkQualityDirect(updateLinkQualitySamples(LINK_QUALITY_MAX_VALUE));
254 setLinkQualityDirect(updateLinkQualitySamples(0));
257 displayClearScreen(&testDisplayPort);
258 osdRefresh(simulationTime);
260 // then
261 displayPortTestBufferSubstring(8, 1, "%c4", SYM_LINK_QUALITY);
265 * Tests the Tests the OSD_LINK_QUALITY element values default LQ_SOURCE_NONE
267 TEST(LQTest, TestElement_LQ_SOURCE_NONE_VALUES)
269 // given
272 linkQualitySource = LQ_SOURCE_NONE;
274 osdElementConfigMutable()->item_pos[OSD_LINK_QUALITY] = OSD_POS(8, 1) | OSD_PROFILE_1_FLAG;
275 osdConfigMutable()->link_quality_alarm = 0;
277 osdAnalyzeActiveElements();
278 // when LINK_QUALITY_MAX_VALUE to 1 by 10%
279 uint16_t testscale = 0;
280 for (int testdigit = 10; testdigit > 0; testdigit--) {
281 testscale = testdigit * 102.3;
282 setLinkQualityDirect(testscale);
283 displayClearScreen(&testDisplayPort);
284 osdRefresh(simulationTime);
285 #ifdef DEBUG_OSD
286 printf("%d %d\n",testscale, testdigit);
287 displayPortTestPrint();
288 #endif
289 // then
290 if (testdigit >= 10) {
291 displayPortTestBufferSubstring(8, 1,"%c9", SYM_LINK_QUALITY);
292 }else{
293 displayPortTestBufferSubstring(8, 1,"%c%1d", SYM_LINK_QUALITY, testdigit - 1);
298 * Tests the OSD_LINK_QUALITY element LQ RX_PROTOCOL_CRSF.
300 TEST(LQTest, TestElementLQ_PROTOCOL_CRSF_VALUES)
302 // given
303 linkQualitySource = LQ_SOURCE_RX_PROTOCOL_CRSF;
305 osdElementConfigMutable()->item_pos[OSD_LINK_QUALITY] = OSD_POS(8, 1) | OSD_PROFILE_1_FLAG;
306 osdConfigMutable()->link_quality_alarm = 0;
308 osdAnalyzeActiveElements();
310 displayClearScreen(&testDisplayPort);
311 osdRefresh(simulationTime);
313 // crsf setLinkQualityDirect 0-300;
315 for (uint8_t x = 0; x <= 99; x++) {
316 for (uint8_t m = 0; m <= 4; m++) {
317 // when x scaled
318 setLinkQualityDirect(x);
319 rxSetRfMode(m);
320 // then rxGetLinkQuality Osd should be x
321 // and RfMode should be m
322 displayClearScreen(&testDisplayPort);
323 osdRefresh(simulationTime);
324 displayPortTestBufferSubstring(8, 1, "%c%1d:%2d", SYM_LINK_QUALITY, m, x);
329 * Tests the LQ Alarms
332 TEST(LQTest, TestLQAlarm)
334 // given
335 // default state is set
336 setDefaultSimulationState();
338 linkQualitySource = LQ_SOURCE_NONE;
340 // and
341 // the following OSD elements are visible
343 osdElementConfigMutable()->item_pos[OSD_LINK_QUALITY] = OSD_POS(8, 1) | OSD_PROFILE_1_FLAG;
345 // and
346 // this set of alarm values
348 osdConfigMutable()->link_quality_alarm = 80;
349 stateFlags |= GPS_FIX | GPS_FIX_HOME;
351 osdAnalyzeActiveElements();
353 // and
354 // using the metric unit system
355 osdConfigMutable()->units = UNIT_METRIC;
357 // when
358 // the craft is armed
359 doTestArm(false);
361 for (int x = 0; x < LINK_QUALITY_SAMPLE_COUNT; x++) {
362 setLinkQualityDirect(updateLinkQualitySamples(LINK_QUALITY_MAX_VALUE));
365 // then
366 // no elements should flash as all values are out of alarm range
367 for (int i = 0; i < 30; i++) {
368 // Check for visibility every 100ms, elements should always be visible
369 simulationTime += 0.1e6;
370 osdRefresh(simulationTime);
372 #ifdef DEBUG_OSD
373 printf("%d\n", i);
374 #endif
375 displayPortTestBufferSubstring(8, 1, "%c9", SYM_LINK_QUALITY);
379 setLinkQualityDirect(512);
380 simulationTime += 60e6;
381 osdRefresh(simulationTime);
383 // then
384 // elements showing values in alarm range should flash
385 for (int i = 0; i < 15; i++) {
386 // Blinking should happen at 5Hz
387 simulationTime += 0.2e6;
388 osdRefresh(simulationTime);
390 #ifdef DEBUG_OSD
391 printf("%d\n", i);
392 displayPortTestPrint();
393 #endif
394 if (i % 2 == 0) {
395 displayPortTestBufferSubstring(8, 1, "%c5", SYM_LINK_QUALITY);
396 } else {
397 displayPortTestBufferIsEmpty();
401 doTestDisarm();
402 simulationTime += 60e6;
403 osdRefresh(simulationTime);
406 // STUBS
407 extern "C" {
409 uint32_t micros() {
410 return simulationTime;
413 uint32_t microsISR() {
414 return micros();
417 uint32_t millis() {
418 return micros() / 1000;
421 bool featureIsEnabled(uint32_t) { return true; }
422 void beeperConfirmationBeeps(uint8_t) {}
423 bool isBeeperOn() { return false; }
424 uint8_t getCurrentPidProfileIndex() { return 0; }
425 uint8_t getCurrentControlRateProfileIndex() { return 0; }
426 batteryState_e getBatteryState() { return BATTERY_OK; }
427 uint8_t getBatteryCellCount() { return 4; }
428 uint16_t getBatteryVoltage() { return 1680; }
429 uint16_t getBatteryAverageCellVoltage() { return 420; }
430 int32_t getAmperage() { return 0; }
431 int32_t getMAhDrawn() { return 0; }
432 int32_t getEstimatedAltitudeCm() { return 0; }
433 int32_t getEstimatedVario() { return 0; }
434 int32_t blackboxGetLogNumber() { return 0; }
435 bool isBlackboxDeviceWorking() { return true; }
436 bool isBlackboxDeviceFull() { return false; }
437 serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;}
438 const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;}
439 bool telemetryCheckRxPortShared(const serialPortConfig_t *) {return false;}
440 bool cmsDisplayPortRegister(displayPort_t *) { return false; }
441 uint16_t getCoreTemperatureCelsius(void) { return 0; }
442 bool isFlipOverAfterCrashActive(void) { return false; }
443 float pidItermAccelerator(void) { return 1.0; }
444 uint8_t getMotorCount(void){ return 4; }
445 bool areMotorsRunning(void){ return true; }
446 bool pidOsdAntiGravityActive(void) { return false; }
447 bool failsafeIsActive(void) { return false; }
448 bool gpsRescueIsConfigured(void) { return false; }
449 int8_t calculateThrottlePercent(void) { return 0; }
450 uint32_t persistentObjectRead(persistentObjectId_e) { return 0; }
451 void persistentObjectWrite(persistentObjectId_e, uint32_t) {}
452 void failsafeOnRxSuspend(uint32_t ) {}
453 void failsafeOnRxResume(void) {}
454 void featureDisableImmediate(uint32_t) { }
455 bool rxMspFrameComplete(void) { return false; }
456 bool isPPMDataBeingReceived(void) { return false; }
457 bool isPWMDataBeingReceived(void) { return false; }
458 void resetPPMDataReceivedState(void){ }
459 void failsafeOnValidDataReceived(void) { }
460 void failsafeOnValidDataFailed(void) { }
461 void pinioBoxTaskControl(void) { }
462 bool taskUpdateRxMainInProgress() { return true; }
464 void rxPwmInit(rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
466 UNUSED(rxRuntimeState);
467 UNUSED(callback);
470 bool sbusInit(rxConfig_t *initialRxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
472 UNUSED(initialRxConfig);
473 UNUSED(rxRuntimeState);
474 UNUSED(callback);
475 return true;
478 bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
480 UNUSED(rxConfig);
481 UNUSED(rxRuntimeState);
482 UNUSED(callback);
483 return true;
486 bool sumdInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
488 UNUSED(rxConfig);
489 UNUSED(rxRuntimeState);
490 UNUSED(callback);
491 return true;
494 bool sumhInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
496 UNUSED(rxConfig);
497 UNUSED(rxRuntimeState);
498 UNUSED(callback);
499 return true;
502 bool crsfRxInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback);
504 bool jetiExBusInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
506 UNUSED(rxConfig);
507 UNUSED(rxRuntimeState);
508 UNUSED(callback);
509 return true;
512 bool ibusInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
514 UNUSED(rxConfig);
515 UNUSED(rxRuntimeState);
516 UNUSED(callback);
517 return true;
520 bool xBusInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
522 UNUSED(rxConfig);
523 UNUSED(rxRuntimeState);
524 UNUSED(callback);
525 return true;
528 bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
530 UNUSED(rxConfig);
531 UNUSED(rxRuntimeState);
532 UNUSED(callback);
533 return true;
536 float pt1FilterGain(float f_cut, float dT)
538 UNUSED(f_cut);
539 UNUSED(dT);
540 return 0.0;
543 void pt1FilterInit(pt1Filter_t *filter, float k)
545 UNUSED(filter);
546 UNUSED(k);
549 float pt1FilterApply(pt1Filter_t *filter, float input)
551 UNUSED(filter);
552 UNUSED(input);
553 return 0.0;
556 bool isUpright(void) { return true; }
558 float getMotorOutputLow(void) { return 1000.0; }
560 float getMotorOutputHigh(void) { return 2047.0; }