Merge pull request #11189 from klutvott123/move-telemetry-displayport-init
[betaflight.git] / src / test / unit / telemetry_crsf_unittest.cc
blob09f79eb4d6c21f781cbaf748a2494dee8e40894c
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 <stdbool.h>
19 #include <stdint.h>
20 #include <string.h>
22 #include <limits.h>
24 extern "C" {
25 #include <platform.h>
27 #include "build/debug.h"
29 #include "common/axis.h"
30 #include "common/crc.h"
31 #include "common/filter.h"
32 #include "common/gps_conversion.h"
33 #include "common/maths.h"
34 #include "common/printf.h"
35 #include "common/typeconversion.h"
37 #include "pg/pg.h"
38 #include "pg/pg_ids.h"
39 #include "pg/rx.h"
41 #include "drivers/serial.h"
42 #include "drivers/system.h"
44 #include "config/config.h"
45 #include "fc/runtime_config.h"
47 #include "flight/pid.h"
48 #include "flight/imu.h"
50 #include "io/gps.h"
51 #include "io/serial.h"
53 #include "rx/rx.h"
54 #include "rx/crsf.h"
56 #include "sensors/battery.h"
57 #include "sensors/sensors.h"
58 #include "sensors/acceleration.h"
60 #include "telemetry/crsf.h"
61 #include "telemetry/telemetry.h"
62 #include "telemetry/msp_shared.h"
64 rssiSource_e rssiSource;
65 bool airMode;
67 uint16_t testBatteryVoltage = 0;
68 int32_t testAmperage = 0;
69 int32_t testmAhDrawn = 0;
71 serialPort_t *telemetrySharedPort;
73 int getCrsfFrame(uint8_t *frame, crsfFrameType_e frameType);
75 PG_REGISTER(batteryConfig_t, batteryConfig, PG_BATTERY_CONFIG, 0);
76 PG_REGISTER(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 0);
77 PG_REGISTER(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 0);
78 PG_REGISTER(rxConfig_t, rxConfig, PG_RX_CONFIG, 0);
79 PG_REGISTER(accelerometerConfig_t, accelerometerConfig, PG_ACCELEROMETER_CONFIG, 0);
82 #include "unittest_macros.h"
83 #include "gtest/gtest.h"
85 uint8_t crfsCrc(uint8_t *frame, int frameLen)
87 uint8_t crc = 0;
88 for (int ii = 2; ii < frameLen - 1; ++ii) {
89 crc = crc8_dvb_s2(crc, frame[ii]);
91 return crc;
95 int32_t Latitude ( degree / 10`000`000 )
96 int32_t Longitude (degree / 10`000`000 )
97 uint16_t Groundspeed ( km/h / 10 )
98 uint16_t GPS heading ( degree / 100 )
99 uint16 Altitude ( meter ­ 1000m offset )
100 uint8_t Satellites in use ( counter )
101 uint16_t GPS_distanceToHome; // distance to home point in meters
103 #define FRAME_HEADER_FOOTER_LEN 4
105 TEST(TelemetryCrsfTest, TestGPS)
107 uint8_t frame[CRSF_FRAME_SIZE_MAX];
109 int frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_GPS);
110 EXPECT_EQ(CRSF_FRAME_GPS_PAYLOAD_SIZE + FRAME_HEADER_FOOTER_LEN, frameLen);
111 EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
112 EXPECT_EQ(17, frame[1]); // length
113 EXPECT_EQ(0x02, frame[2]); // type
114 int32_t lattitude = frame[3] << 24 | frame[4] << 16 | frame[5] << 8 | frame[6];
115 EXPECT_EQ(0, lattitude);
116 int32_t longitude = frame[7] << 24 | frame[8] << 16 | frame[9] << 8 | frame[10];
117 EXPECT_EQ(0, longitude);
118 uint16_t groundSpeed = frame[11] << 8 | frame[12];
119 EXPECT_EQ(0, groundSpeed);
120 uint16_t GPSheading = frame[13] << 8 | frame[14];
121 EXPECT_EQ(0, GPSheading);
122 uint16_t altitude = frame[15] << 8 | frame[16];
123 EXPECT_EQ(1000, altitude);
124 uint8_t satelliteCount = frame[17];
125 EXPECT_EQ(0, satelliteCount);
126 EXPECT_EQ(crfsCrc(frame, frameLen), frame[18]);
128 gpsSol.llh.lat = 56 * GPS_DEGREES_DIVIDER;
129 gpsSol.llh.lon = 163 * GPS_DEGREES_DIVIDER;
130 ENABLE_STATE(GPS_FIX);
131 gpsSol.llh.altCm = 2345 * 100; // altitude in cm / 100 + 1000m offset, so CRSF value should be 3345
132 gpsSol.groundSpeed = 1630; // speed in cm/s, 16.3 m/s = 58.68 km/h, so CRSF (km/h *10) value is 587
133 gpsSol.numSat = 9;
134 gpsSol.groundCourse = 1479; // degrees * 10
135 frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_GPS);
136 lattitude = frame[3] << 24 | frame[4] << 16 | frame[5] << 8 | frame[6];
137 EXPECT_EQ(560000000, lattitude);
138 longitude = frame[7] << 24 | frame[8] << 16 | frame[9] << 8 | frame[10];
139 EXPECT_EQ(1630000000, longitude);
140 groundSpeed = frame[11] << 8 | frame[12];
141 EXPECT_EQ(587, groundSpeed);
142 GPSheading = frame[13] << 8 | frame[14];
143 EXPECT_EQ(14790, GPSheading);
144 altitude = frame[15] << 8 | frame[16];
145 EXPECT_EQ(3345, altitude);
146 satelliteCount = frame[17];
147 EXPECT_EQ(9, satelliteCount);
148 EXPECT_EQ(crfsCrc(frame, frameLen), frame[18]);
151 TEST(TelemetryCrsfTest, TestBattery)
153 uint8_t frame[CRSF_FRAME_SIZE_MAX];
155 testBatteryVoltage = 0; // 0.1V units
156 int frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_BATTERY_SENSOR);
157 EXPECT_EQ(CRSF_FRAME_BATTERY_SENSOR_PAYLOAD_SIZE + FRAME_HEADER_FOOTER_LEN, frameLen);
158 EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
159 EXPECT_EQ(10, frame[1]); // length
160 EXPECT_EQ(0x08, frame[2]); // type
161 uint16_t voltage = frame[3] << 8 | frame[4]; // mV * 100
162 EXPECT_EQ(0, voltage);
163 uint16_t current = frame[5] << 8 | frame[6]; // mA * 100
164 EXPECT_EQ(0, current);
165 uint32_t capacity = frame[7] << 16 | frame[8] << 8 | frame [9]; // mAh
166 EXPECT_EQ(0, capacity);
167 uint16_t remaining = frame[10]; // percent
168 EXPECT_EQ(67, remaining);
169 EXPECT_EQ(crfsCrc(frame, frameLen), frame[11]);
171 testBatteryVoltage = 330; // 3.3V = 3300 mv
172 testAmperage = 2960; // = 29.60A = 29600mA - amperage is in 0.01A steps
173 testmAhDrawn = 1234;
174 frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_BATTERY_SENSOR);
175 voltage = frame[3] << 8 | frame[4]; // mV * 100
176 EXPECT_EQ(33, voltage);
177 current = frame[5] << 8 | frame[6]; // mA * 100
178 EXPECT_EQ(296, current);
179 capacity = frame[7] << 16 | frame[8] << 8 | frame [9]; // mAh
180 EXPECT_EQ(1234, capacity);
181 remaining = frame[10]; // percent
182 EXPECT_EQ(67, remaining);
183 EXPECT_EQ(crfsCrc(frame, frameLen), frame[11]);
186 TEST(TelemetryCrsfTest, TestAttitude)
188 uint8_t frame[CRSF_FRAME_SIZE_MAX];
190 attitude.values.pitch = 0;
191 attitude.values.roll = 0;
192 attitude.values.yaw = 0;
193 int frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_ATTITUDE);
194 EXPECT_EQ(CRSF_FRAME_ATTITUDE_PAYLOAD_SIZE + FRAME_HEADER_FOOTER_LEN, frameLen);
195 EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
196 EXPECT_EQ(8, frame[1]); // length
197 EXPECT_EQ(0x1e, frame[2]); // type
198 int16_t pitch = frame[3] << 8 | frame[4]; // rad / 10000
199 EXPECT_EQ(0, pitch);
200 int16_t roll = frame[5] << 8 | frame[6];
201 EXPECT_EQ(0, roll);
202 int16_t yaw = frame[7] << 8 | frame[8];
203 EXPECT_EQ(0, yaw);
204 EXPECT_EQ(crfsCrc(frame, frameLen), frame[9]);
206 attitude.values.pitch = 678; // decidegrees == 1.183333232852155 rad
207 attitude.values.roll = 1495; // 2.609267231731523 rad
208 attitude.values.yaw = -1799; //3.139847324337799 rad
209 frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_ATTITUDE);
210 pitch = frame[3] << 8 | frame[4]; // rad / 10000
211 EXPECT_EQ(11833, pitch);
212 roll = frame[5] << 8 | frame[6];
213 EXPECT_EQ(26092, roll);
214 yaw = frame[7] << 8 | frame[8];
215 EXPECT_EQ(-31398, yaw);
216 EXPECT_EQ(crfsCrc(frame, frameLen), frame[9]);
219 TEST(TelemetryCrsfTest, TestFlightMode)
221 uint8_t frame[CRSF_FRAME_SIZE_MAX];
223 ENABLE_STATE(GPS_FIX);
224 ENABLE_STATE(GPS_FIX_HOME);
226 airMode = false;
228 DISABLE_ARMING_FLAG(ARMED);
230 // nothing set, so ACRO mode
231 int frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_FLIGHT_MODE);
232 EXPECT_EQ(6 + FRAME_HEADER_FOOTER_LEN, frameLen);
233 EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
234 EXPECT_EQ(8, frame[1]); // length
235 EXPECT_EQ(0x21, frame[2]); // type
236 EXPECT_EQ('A', frame[3]);
237 EXPECT_EQ('C', frame[4]);
238 EXPECT_EQ('R', frame[5]);
239 EXPECT_EQ('O', frame[6]);
240 EXPECT_EQ('*', frame[7]);
241 EXPECT_EQ(0, frame[8]);
242 EXPECT_EQ(crfsCrc(frame, frameLen), frame[9]);
244 ENABLE_ARMING_FLAG(ARMED);
246 frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_FLIGHT_MODE);
247 EXPECT_EQ(5 + FRAME_HEADER_FOOTER_LEN, frameLen);
248 EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
249 EXPECT_EQ(7, frame[1]); // length
250 EXPECT_EQ(0x21, frame[2]); // type
251 EXPECT_EQ('A', frame[3]);
252 EXPECT_EQ('C', frame[4]);
253 EXPECT_EQ('R', frame[5]);
254 EXPECT_EQ('O', frame[6]);
255 EXPECT_EQ(0, frame[7]);
256 EXPECT_EQ(crfsCrc(frame, frameLen), frame[8]);
258 enableFlightMode(ANGLE_MODE);
259 EXPECT_EQ(ANGLE_MODE, FLIGHT_MODE(ANGLE_MODE));
260 frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_FLIGHT_MODE);
261 EXPECT_EQ(5 + FRAME_HEADER_FOOTER_LEN, frameLen);
262 EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
263 EXPECT_EQ(7, frame[1]); // length
264 EXPECT_EQ(0x21, frame[2]); // type
265 EXPECT_EQ('S', frame[3]);
266 EXPECT_EQ('T', frame[4]);
267 EXPECT_EQ('A', frame[5]);
268 EXPECT_EQ('B', frame[6]);
269 EXPECT_EQ(0, frame[7]);
270 EXPECT_EQ(crfsCrc(frame, frameLen), frame[8]);
272 disableFlightMode(ANGLE_MODE);
273 enableFlightMode(HORIZON_MODE);
274 EXPECT_EQ(HORIZON_MODE, FLIGHT_MODE(HORIZON_MODE));
275 frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_FLIGHT_MODE);
276 EXPECT_EQ(4 + FRAME_HEADER_FOOTER_LEN, frameLen);
277 EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
278 EXPECT_EQ(6, frame[1]); // length
279 EXPECT_EQ(0x21, frame[2]); // type
280 EXPECT_EQ('H', frame[3]);
281 EXPECT_EQ('O', frame[4]);
282 EXPECT_EQ('R', frame[5]);
283 EXPECT_EQ(0, frame[6]);
284 EXPECT_EQ(crfsCrc(frame, frameLen), frame[7]);
286 disableFlightMode(HORIZON_MODE);
287 airMode = true;
288 frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_FLIGHT_MODE);
289 EXPECT_EQ(4 + FRAME_HEADER_FOOTER_LEN, frameLen);
290 EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
291 EXPECT_EQ(6, frame[1]); // length
292 EXPECT_EQ(0x21, frame[2]); // type
293 EXPECT_EQ('A', frame[3]);
294 EXPECT_EQ('I', frame[4]);
295 EXPECT_EQ('R', frame[5]);
296 EXPECT_EQ(0, frame[6]);
297 EXPECT_EQ(crfsCrc(frame, frameLen), frame[7]);
300 // STUBS
302 extern "C" {
304 int16_t debug[DEBUG16_VALUE_COUNT];
306 const uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000, 400000}; // see baudRate_e
308 uint16_t batteryWarningVoltage;
309 uint8_t useHottAlarmSoundPeriod (void) { return 0; }
311 attitudeEulerAngles_t attitude = { { 0, 0, 0 } }; // absolute angle inclination in multiple of 0.1 degree 180 deg = 1800
313 uint16_t GPS_distanceToHome; // distance to home point in meters
314 gpsSolutionData_t gpsSol;
316 void beeperConfirmationBeeps(uint8_t beepCount) {UNUSED(beepCount);}
318 uint32_t micros(void) {return 0;}
319 uint32_t microsISR(void) {return micros();}
321 bool featureIsEnabled(uint32_t) {return true;}
323 uint32_t serialRxBytesWaiting(const serialPort_t *) {return 0;}
324 uint32_t serialTxBytesFree(const serialPort_t *) {return 0;}
325 uint8_t serialRead(serialPort_t *) {return 0;}
326 void serialWrite(serialPort_t *, uint8_t) {}
327 void serialWriteBuf(serialPort_t *, const uint8_t *, int) {}
328 void serialSetMode(serialPort_t *, portMode_e) {}
329 serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;}
330 void closeSerialPort(serialPort_t *) {}
331 bool isSerialTransmitBufferEmpty(const serialPort_t *) { return true; }
333 const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e) {return NULL;}
335 bool telemetryDetermineEnabledState(portSharing_e) {return true;}
336 bool telemetryCheckRxPortShared(const serialPortConfig_t *, SerialRXType) {return true;}
337 bool telemetryIsSensorEnabled(sensor_e) {return true;}
339 portSharing_e determinePortSharing(const serialPortConfig_t *, serialPortFunction_e) {return PORTSHARING_NOT_SHARED;}
341 bool airmodeIsEnabled(void) {return airMode;}
343 int32_t getAmperage(void) {
344 return testAmperage;
347 uint16_t getBatteryVoltage(void) {
348 return testBatteryVoltage;
351 uint16_t getLegacyBatteryVoltage(void) {
352 return (testBatteryVoltage + 5) / 10;
355 uint16_t getBatteryAverageCellVoltage(void) {
356 return 0;
359 batteryState_e getBatteryState(void) {
360 return BATTERY_OK;
363 uint8_t calculateBatteryPercentageRemaining(void) {
364 return 67;
367 int32_t getEstimatedAltitudeCm(void) {
368 return gpsSol.llh.altCm; // function returns cm not m.
371 int32_t getMAhDrawn(void){
372 return testmAhDrawn;
375 bool sendMspReply(uint8_t, mspResponseFnPtr) { return false; }
376 bool handleMspFrame(uint8_t *, uint8_t, uint8_t *) { return false; }
377 bool isBatteryVoltageConfigured(void) { return true; }
378 bool isAmperageConfigured(void) { return true; }
379 timeUs_t rxFrameTimeUs(void) { return 0; }