Improved fixed wing detection. (#9186)
[betaflight.git] / src / test / unit / link_quality_unittest.cc
blobc22ae1c6d6ac9c3e8aa0f99cc96ab24aa8a7746f
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/time.h"
31 #include "common/crc.h"
32 #include "common/utils.h"
33 #include "common/printf.h"
34 #include "common/streambuf.h"
36 #include "drivers/max7456_symbols.h"
37 #include "drivers/persistent.h"
38 #include "drivers/serial.h"
39 #include "drivers/system.h"
41 #include "config/config.h"
42 #include "fc/core.h"
43 #include "fc/rc_controls.h"
44 #include "fc/rc_modes.h"
45 #include "fc/runtime_config.h"
47 #include "flight/mixer.h"
48 #include "flight/pid.h"
49 #include "flight/imu.h"
51 #include "io/beeper.h"
52 #include "io/gps.h"
53 #include "io/serial.h"
55 #include "osd/osd.h"
56 #include "osd/osd_elements.h"
58 #include "pg/pg.h"
59 #include "pg/pg_ids.h"
60 #include "pg/rx.h"
62 #include "rx/rx.h"
64 #include "sensors/battery.h"
66 attitudeEulerAngles_t attitude;
67 pidProfile_t *currentPidProfile;
68 int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
69 uint8_t GPS_numSat;
70 uint16_t GPS_distanceToHome;
71 int16_t GPS_directionToHome;
72 uint32_t GPS_distanceFlownInCm;
73 int32_t GPS_coord[2];
74 gpsSolutionData_t gpsSol;
75 float motor[8];
76 float motorOutputHigh = 2047;
77 float motorOutputLow = 1000;
78 acc_t acc;
79 float accAverage[XYZ_AXIS_COUNT];
81 PG_REGISTER(batteryConfig_t, batteryConfig, PG_BATTERY_CONFIG, 0);
82 PG_REGISTER(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 0);
83 PG_REGISTER(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 0);
84 PG_REGISTER(pilotConfig_t, pilotConfig, PG_PILOT_CONFIG, 0);
85 PG_REGISTER(imuConfig_t, imuConfig, PG_IMU_CONFIG, 0);
86 PG_REGISTER(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 0);
88 timeUs_t simulationTime = 0;
90 void osdRefresh(timeUs_t currentTimeUs);
91 uint16_t updateLinkQualitySamples(uint16_t value);
92 uint16_t scaleCrsfLq(uint16_t lqvalue);
93 #define LINK_QUALITY_SAMPLE_COUNT 16
96 /* #define DEBUG_OSD */
98 #include "unittest_macros.h"
99 #include "unittest_displayport.h"
100 #include "gtest/gtest.h"
102 extern "C" {
103 PG_REGISTER(flight3DConfig_t, flight3DConfig, PG_MOTOR_3D_CONFIG, 0);
105 boxBitmask_t rcModeActivationMask;
106 int16_t debug[DEBUG16_VALUE_COUNT];
107 uint8_t debugMode = 0;
109 uint16_t updateLinkQualitySamples(uint16_t value);
111 extern uint16_t applyRxChannelRangeConfiguraton(int sample, const rxChannelRangeConfig_t *range);
113 void setDefaultSimulationState()
116 setLinkQualityDirect(LINK_QUALITY_MAX_VALUE);
120 * Performs a test of the OSD actions on arming.
121 * (reused throughout the test suite)
123 void doTestArm(bool testEmpty = true)
125 // given
126 // craft has been armed
127 ENABLE_ARMING_FLAG(ARMED);
129 // when
130 // sufficient OSD updates have been called
131 osdRefresh(simulationTime);
133 // then
134 // arming alert displayed
135 displayPortTestBufferSubstring(12, 7, "ARMED");
137 // given
138 // armed alert times out (0.5 seconds)
139 simulationTime += 0.5e6;
141 // when
142 // sufficient OSD updates have been called
143 osdRefresh(simulationTime);
145 // then
146 // arming alert disappears
147 #ifdef DEBUG_OSD
148 displayPortTestPrint();
149 #endif
150 if (testEmpty) {
151 displayPortTestBufferIsEmpty();
156 * Auxiliary function. Test is there're stats that must be shown
158 bool isSomeStatEnabled(void) {
159 return (osdConfigMutable()->enabled_stats != 0);
163 * Performs a test of the OSD actions on disarming.
164 * (reused throughout the test suite)
166 void doTestDisarm()
168 // given
169 // craft is disarmed after having been armed
170 DISABLE_ARMING_FLAG(ARMED);
172 // when
173 // sufficient OSD updates have been called
174 osdRefresh(simulationTime);
176 // then
177 // post flight statistics displayed
178 if (isSomeStatEnabled()) {
179 displayPortTestBufferSubstring(2, 2, " --- STATS ---");
184 * Tests initialisation of the OSD and the power on splash screen.
186 TEST(LQTest, TestInit)
188 // given
189 // display port is initialised
190 displayPortTestInit();
192 // and
193 // default state values are set
194 setDefaultSimulationState();
196 // and
197 // this battery configuration (used for battery voltage elements)
198 batteryConfigMutable()->vbatmincellvoltage = 330;
199 batteryConfigMutable()->vbatmaxcellvoltage = 430;
201 // when
202 // OSD is initialised
203 osdInit(&testDisplayPort);
205 // then
206 // display buffer should contain splash screen
207 displayPortTestBufferSubstring(7, 8, "MENU:THR MID");
208 displayPortTestBufferSubstring(11, 9, "+ YAW LEFT");
209 displayPortTestBufferSubstring(11, 10, "+ PITCH UP");
211 // when
212 // splash screen timeout has elapsed
213 simulationTime += 4e6;
214 osdUpdate(simulationTime);
216 // then
217 // display buffer should be empty
218 #ifdef DEBUG_OSD
219 displayPortTestPrint();
220 #endif
221 displayPortTestBufferIsEmpty();
224 * Tests the Tests the OSD_LINK_QUALITY element updateLinkQualitySamples default LQ_SOURCE_NONE
226 TEST(LQTest, TestElement_LQ_SOURCE_NONE_SAMPLES)
228 // given
231 linkQualitySource = LQ_SOURCE_NONE;
233 osdConfigMutable()->item_pos[OSD_LINK_QUALITY] = OSD_POS(8, 1) | OSD_PROFILE_1_FLAG;
234 osdConfigMutable()->link_quality_alarm = 0;
236 osdAnalyzeActiveElements();
238 // when samples populated 100%
239 for (int x = 0; x < LINK_QUALITY_SAMPLE_COUNT; x++) {
240 setLinkQualityDirect(updateLinkQualitySamples(LINK_QUALITY_MAX_VALUE));
244 displayClearScreen(&testDisplayPort);
245 osdRefresh(simulationTime);
247 // then
248 displayPortTestBufferSubstring(8, 1, "%c9", SYM_LINK_QUALITY);
250 // when updateLinkQualitySamples used 50% rounds to 4
251 for (int x = 0; x < LINK_QUALITY_SAMPLE_COUNT; x++) {
252 setLinkQualityDirect(updateLinkQualitySamples(LINK_QUALITY_MAX_VALUE));
253 setLinkQualityDirect(updateLinkQualitySamples(0));
256 displayClearScreen(&testDisplayPort);
257 osdRefresh(simulationTime);
259 // then
260 displayPortTestBufferSubstring(8, 1, "%c4", SYM_LINK_QUALITY);
264 * Tests the Tests the OSD_LINK_QUALITY element values default LQ_SOURCE_NONE
266 TEST(LQTest, TestElement_LQ_SOURCE_NONE_VALUES)
268 // given
271 linkQualitySource = LQ_SOURCE_NONE;
273 osdConfigMutable()->item_pos[OSD_LINK_QUALITY] = OSD_POS(8, 1) | OSD_PROFILE_1_FLAG;
274 osdConfigMutable()->link_quality_alarm = 0;
276 osdAnalyzeActiveElements();
277 // when LINK_QUALITY_MAX_VALUE to 1 by 10%
278 uint16_t testscale = 0;
279 for (int testdigit = 10; testdigit > 0; testdigit--) {
280 testscale = testdigit * 102.3;
281 setLinkQualityDirect(testscale);
282 displayClearScreen(&testDisplayPort);
283 osdRefresh(simulationTime);
284 #ifdef DEBUG_OSD
285 printf("%d %d\n",testscale, testdigit);
286 displayPortTestPrint();
287 #endif
288 // then
289 if (testdigit >= 10){
290 displayPortTestBufferSubstring(8, 1,"%c9", SYM_LINK_QUALITY);
291 }else{
292 displayPortTestBufferSubstring(8, 1,"%c%1d", SYM_LINK_QUALITY, testdigit - 1);
297 * Tests the OSD_LINK_QUALITY element LQ RX_PROTOCOL_CRSF.
299 TEST(LQTest, TestElementLQ_PROTOCOL_CRSF_VALUES)
301 // given
302 linkQualitySource = LQ_SOURCE_RX_PROTOCOL_CRSF;
304 osdConfigMutable()->item_pos[OSD_LINK_QUALITY] = OSD_POS(8, 1) | OSD_PROFILE_1_FLAG;
305 osdConfigMutable()->link_quality_alarm = 0;
307 osdAnalyzeActiveElements();
309 displayClearScreen(&testDisplayPort);
310 osdRefresh(simulationTime);
312 // crsf setLinkQualityDirect 0-300;
314 for (uint16_t x = 0; x <= 300; x++) {
315 // when x scaled
316 setLinkQualityDirect(scaleCrsfLq(x));
317 // then rxGetLinkQuality Osd should be x
318 displayClearScreen(&testDisplayPort);
319 osdRefresh(simulationTime);
320 displayPortTestBufferSubstring(8, 1,"%c%3d", SYM_LINK_QUALITY, x);
325 * Tests the LQ Alarms
328 TEST(LQTest, TestLQAlarm)
330 // given
331 // default state is set
332 setDefaultSimulationState();
334 linkQualitySource = LQ_SOURCE_NONE;
336 // and
337 // the following OSD elements are visible
339 osdConfigMutable()->item_pos[OSD_LINK_QUALITY] = OSD_POS(8, 1) | OSD_PROFILE_1_FLAG;
341 // and
342 // this set of alarm values
344 osdConfigMutable()->link_quality_alarm = 80;
345 stateFlags |= GPS_FIX | GPS_FIX_HOME;
347 osdAnalyzeActiveElements();
349 // and
350 // using the metric unit system
351 osdConfigMutable()->units = OSD_UNIT_METRIC;
353 // when
354 // the craft is armed
355 doTestArm(false);
357 for (int x = 0; x < LINK_QUALITY_SAMPLE_COUNT; x++) {
358 setLinkQualityDirect(updateLinkQualitySamples(LINK_QUALITY_MAX_VALUE));
361 // then
362 // no elements should flash as all values are out of alarm range
363 for (int i = 0; i < 30; i++) {
364 // Check for visibility every 100ms, elements should always be visible
365 simulationTime += 0.1e6;
366 osdRefresh(simulationTime);
368 #ifdef DEBUG_OSD
369 printf("%d\n", i);
370 #endif
371 displayPortTestBufferSubstring(8, 1, "%c9", SYM_LINK_QUALITY);
375 setLinkQualityDirect(512);
376 simulationTime += 60e6;
377 osdRefresh(simulationTime);
379 // then
380 // elements showing values in alarm range should flash
381 for (int i = 0; i < 15; i++) {
382 // Blinking should happen at 5Hz
383 simulationTime += 0.2e6;
384 osdRefresh(simulationTime);
386 #ifdef DEBUG_OSD
387 printf("%d\n", i);
388 displayPortTestPrint();
389 #endif
390 if (i % 2 == 0) {
391 displayPortTestBufferSubstring(8, 1, "%c5", SYM_LINK_QUALITY);
392 } else {
393 displayPortTestBufferIsEmpty();
397 doTestDisarm();
398 simulationTime += 60e6;
399 osdRefresh(simulationTime);
402 // STUBS
403 extern "C" {
405 uint32_t micros() {
406 return simulationTime;
409 uint32_t millis() {
410 return micros() / 1000;
413 bool featureIsEnabled(uint32_t) { return true; }
414 void beeperConfirmationBeeps(uint8_t) {}
415 bool isBeeperOn() { return false; }
416 uint8_t getCurrentPidProfileIndex() { return 0; }
417 uint8_t getCurrentControlRateProfileIndex() { return 0; }
418 batteryState_e getBatteryState() { return BATTERY_OK; }
419 uint8_t getBatteryCellCount() { return 4; }
420 uint16_t getBatteryVoltage() { return 1680; }
421 uint16_t getBatteryAverageCellVoltage() { return 420; }
422 int32_t getAmperage() { return 0; }
423 int32_t getMAhDrawn() { return 0; }
424 int32_t getEstimatedAltitudeCm() { return 0; }
425 int32_t getEstimatedVario() { return 0; }
426 int32_t blackboxGetLogNumber() { return 0; }
427 bool isBlackboxDeviceWorking() { return true; }
428 bool isBlackboxDeviceFull() { return false; }
429 serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;}
430 serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;}
431 bool telemetryCheckRxPortShared(const serialPortConfig_t *) {return false;}
432 bool cmsDisplayPortRegister(displayPort_t *) { return false; }
433 uint16_t getCoreTemperatureCelsius(void) { return 0; }
434 bool isFlipOverAfterCrashActive(void) { return false; }
435 float pidItermAccelerator(void) { return 1.0; }
436 uint8_t getMotorCount(void){ return 4; }
437 bool areMotorsRunning(void){ return true; }
438 bool pidOsdAntiGravityActive(void) { return false; }
439 bool failsafeIsActive(void) { return false; }
440 bool gpsRescueIsConfigured(void) { return false; }
441 int8_t calculateThrottlePercent(void) { return 0; }
442 uint32_t persistentObjectRead(persistentObjectId_e) { return 0; }
443 void persistentObjectWrite(persistentObjectId_e, uint32_t) {}
444 void failsafeOnRxSuspend(uint32_t ) {}
445 void failsafeOnRxResume(void) {}
446 void featureDisable(uint32_t) { }
447 bool rxMspFrameComplete(void) { return false; }
448 bool isPPMDataBeingReceived(void) { return false; }
449 bool isPWMDataBeingReceived(void) { return false; }
450 void resetPPMDataReceivedState(void){ }
451 void failsafeOnValidDataReceived(void) { }
452 void failsafeOnValidDataFailed(void) { }
454 void rxPwmInit(rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
456 UNUSED(rxRuntimeState);
457 UNUSED(callback);
460 bool sbusInit(rxConfig_t *initialRxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
462 UNUSED(initialRxConfig);
463 UNUSED(rxRuntimeState);
464 UNUSED(callback);
465 return true;
468 bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
470 UNUSED(rxConfig);
471 UNUSED(rxRuntimeState);
472 UNUSED(callback);
473 return true;
476 bool sumdInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
478 UNUSED(rxConfig);
479 UNUSED(rxRuntimeState);
480 UNUSED(callback);
481 return true;
484 bool sumhInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
486 UNUSED(rxConfig);
487 UNUSED(rxRuntimeState);
488 UNUSED(callback);
489 return true;
492 bool crsfRxInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback);
494 bool jetiExBusInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
496 UNUSED(rxConfig);
497 UNUSED(rxRuntimeState);
498 UNUSED(callback);
499 return true;
502 bool ibusInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
504 UNUSED(rxConfig);
505 UNUSED(rxRuntimeState);
506 UNUSED(callback);
507 return true;
510 bool xBusInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
512 UNUSED(rxConfig);
513 UNUSED(rxRuntimeState);
514 UNUSED(callback);
515 return true;
518 bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
520 UNUSED(rxConfig);
521 UNUSED(rxRuntimeState);
522 UNUSED(callback);
523 return true;
526 float pt1FilterGain(float f_cut, float dT)
528 UNUSED(f_cut);
529 UNUSED(dT);
530 return 0.0;
533 void pt1FilterInit(pt1Filter_t *filter, float k)
535 UNUSED(filter);
536 UNUSED(k);
539 float pt1FilterApply(pt1Filter_t *filter, float input)
541 UNUSED(filter);
542 UNUSED(input);
543 return 0.0;