Center ARMED message and stats (#12086)
[betaflight.git] / src / test / unit / telemetry_crsf_unittest.cc
blob270a085c790ac211004095437aae73d6497d5207
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 "msp/msp_serial.h"
62 #include "telemetry/crsf.h"
63 #include "telemetry/telemetry.h"
64 #include "telemetry/msp_shared.h"
66 rssiSource_e rssiSource;
67 bool airMode;
69 uint16_t testBatteryVoltage = 0;
70 int32_t testAmperage = 0;
71 int32_t testmAhDrawn = 0;
73 serialPort_t *telemetrySharedPort;
75 int getCrsfFrame(uint8_t *frame, crsfFrameType_e frameType);
77 PG_REGISTER(batteryConfig_t, batteryConfig, PG_BATTERY_CONFIG, 0);
78 PG_REGISTER(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 0);
79 PG_REGISTER(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 0);
80 PG_REGISTER(rxConfig_t, rxConfig, PG_RX_CONFIG, 0);
81 PG_REGISTER(accelerometerConfig_t, accelerometerConfig, PG_ACCELEROMETER_CONFIG, 0);
84 #include "unittest_macros.h"
85 #include "gtest/gtest.h"
87 uint8_t crfsCrc(uint8_t *frame, int frameLen)
89 uint8_t crc = 0;
90 for (int ii = 2; ii < frameLen - 1; ++ii) {
91 crc = crc8_dvb_s2(crc, frame[ii]);
93 return crc;
97 int32_t Latitude ( degree / 10`000`000 )
98 int32_t Longitude (degree / 10`000`000 )
99 uint16_t Groundspeed ( km/h / 10 )
100 uint16_t GPS heading ( degree / 100 )
101 uint16 Altitude ( meter ­ 1000m offset )
102 uint8_t Satellites in use ( counter )
103 uint16_t GPS_distanceToHome; // distance to home point in meters
105 #define FRAME_HEADER_FOOTER_LEN 4
107 TEST(TelemetryCrsfTest, TestGPS)
109 uint8_t frame[CRSF_FRAME_SIZE_MAX];
111 int frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_GPS);
112 EXPECT_EQ(CRSF_FRAME_GPS_PAYLOAD_SIZE + FRAME_HEADER_FOOTER_LEN, frameLen);
113 EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
114 EXPECT_EQ(17, frame[1]); // length
115 EXPECT_EQ(0x02, frame[2]); // type
116 int32_t lattitude = frame[3] << 24 | frame[4] << 16 | frame[5] << 8 | frame[6];
117 EXPECT_EQ(0, lattitude);
118 int32_t longitude = frame[7] << 24 | frame[8] << 16 | frame[9] << 8 | frame[10];
119 EXPECT_EQ(0, longitude);
120 uint16_t groundSpeed = frame[11] << 8 | frame[12];
121 EXPECT_EQ(0, groundSpeed);
122 uint16_t GPSheading = frame[13] << 8 | frame[14];
123 EXPECT_EQ(0, GPSheading);
124 uint16_t altitude = frame[15] << 8 | frame[16];
125 EXPECT_EQ(1000, altitude);
126 uint8_t satelliteCount = frame[17];
127 EXPECT_EQ(0, satelliteCount);
128 EXPECT_EQ(crfsCrc(frame, frameLen), frame[18]);
130 gpsSol.llh.lat = 56 * GPS_DEGREES_DIVIDER;
131 gpsSol.llh.lon = 163 * GPS_DEGREES_DIVIDER;
132 ENABLE_STATE(GPS_FIX);
133 gpsSol.llh.altCm = 2345 * 100; // altitude in cm / 100 + 1000m offset, so CRSF value should be 3345
134 gpsSol.groundSpeed = 1630; // speed in cm/s, 16.3 m/s = 58.68 km/h, so CRSF (km/h *10) value is 587
135 gpsSol.numSat = 9;
136 gpsSol.groundCourse = 1479; // degrees * 10
137 frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_GPS);
138 lattitude = frame[3] << 24 | frame[4] << 16 | frame[5] << 8 | frame[6];
139 EXPECT_EQ(560000000, lattitude);
140 longitude = frame[7] << 24 | frame[8] << 16 | frame[9] << 8 | frame[10];
141 EXPECT_EQ(1630000000, longitude);
142 groundSpeed = frame[11] << 8 | frame[12];
143 EXPECT_EQ(587, groundSpeed);
144 GPSheading = frame[13] << 8 | frame[14];
145 EXPECT_EQ(14790, GPSheading);
146 altitude = frame[15] << 8 | frame[16];
147 EXPECT_EQ(3345, altitude);
148 satelliteCount = frame[17];
149 EXPECT_EQ(9, satelliteCount);
150 EXPECT_EQ(crfsCrc(frame, frameLen), frame[18]);
153 TEST(TelemetryCrsfTest, TestBattery)
155 uint8_t frame[CRSF_FRAME_SIZE_MAX];
157 testBatteryVoltage = 0; // 0.1V units
158 int frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_BATTERY_SENSOR);
159 EXPECT_EQ(CRSF_FRAME_BATTERY_SENSOR_PAYLOAD_SIZE + FRAME_HEADER_FOOTER_LEN, frameLen);
160 EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
161 EXPECT_EQ(10, frame[1]); // length
162 EXPECT_EQ(0x08, frame[2]); // type
163 uint16_t voltage = frame[3] << 8 | frame[4]; // mV * 100
164 EXPECT_EQ(0, voltage);
165 uint16_t current = frame[5] << 8 | frame[6]; // mA * 100
166 EXPECT_EQ(0, current);
167 uint32_t capacity = frame[7] << 16 | frame[8] << 8 | frame [9]; // mAh
168 EXPECT_EQ(0, capacity);
169 uint16_t remaining = frame[10]; // percent
170 EXPECT_EQ(67, remaining);
171 EXPECT_EQ(crfsCrc(frame, frameLen), frame[11]);
173 testBatteryVoltage = 330; // 3.3V = 3300 mv
174 testAmperage = 2960; // = 29.60A = 29600mA - amperage is in 0.01A steps
175 testmAhDrawn = 1234;
176 frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_BATTERY_SENSOR);
177 voltage = frame[3] << 8 | frame[4]; // mV * 100
178 EXPECT_EQ(33, voltage);
179 current = frame[5] << 8 | frame[6]; // mA * 100
180 EXPECT_EQ(296, current);
181 capacity = frame[7] << 16 | frame[8] << 8 | frame [9]; // mAh
182 EXPECT_EQ(1234, capacity);
183 remaining = frame[10]; // percent
184 EXPECT_EQ(67, remaining);
185 EXPECT_EQ(crfsCrc(frame, frameLen), frame[11]);
188 TEST(TelemetryCrsfTest, TestAttitude)
190 uint8_t frame[CRSF_FRAME_SIZE_MAX];
192 attitude.values.pitch = 0;
193 attitude.values.roll = 0;
194 attitude.values.yaw = 0;
195 int frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_ATTITUDE);
196 EXPECT_EQ(CRSF_FRAME_ATTITUDE_PAYLOAD_SIZE + FRAME_HEADER_FOOTER_LEN, frameLen);
197 EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
198 EXPECT_EQ(8, frame[1]); // length
199 EXPECT_EQ(0x1e, frame[2]); // type
200 int16_t pitch = frame[3] << 8 | frame[4]; // rad / 10000
201 EXPECT_EQ(0, pitch);
202 int16_t roll = frame[5] << 8 | frame[6];
203 EXPECT_EQ(0, roll);
204 int16_t yaw = frame[7] << 8 | frame[8];
205 EXPECT_EQ(0, yaw);
206 EXPECT_EQ(crfsCrc(frame, frameLen), frame[9]);
208 attitude.values.pitch = 678; // decidegrees == 1.183333232852155 rad
209 attitude.values.roll = 1495; // 2.609267231731523 rad
210 attitude.values.yaw = -1799; //3.139847324337799 rad
211 frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_ATTITUDE);
212 pitch = frame[3] << 8 | frame[4]; // rad / 10000
213 EXPECT_EQ(11833, pitch);
214 roll = frame[5] << 8 | frame[6];
215 EXPECT_EQ(26092, roll);
216 yaw = frame[7] << 8 | frame[8];
217 EXPECT_EQ(-31398, yaw);
218 EXPECT_EQ(crfsCrc(frame, frameLen), frame[9]);
221 TEST(TelemetryCrsfTest, TestFlightMode)
223 uint8_t frame[CRSF_FRAME_SIZE_MAX];
225 ENABLE_STATE(GPS_FIX);
226 ENABLE_STATE(GPS_FIX_HOME);
228 airMode = false;
230 DISABLE_ARMING_FLAG(ARMED);
232 // nothing set, so ACRO mode
233 int frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_FLIGHT_MODE);
234 EXPECT_EQ(6 + FRAME_HEADER_FOOTER_LEN, frameLen);
235 EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
236 EXPECT_EQ(8, frame[1]); // length
237 EXPECT_EQ(0x21, frame[2]); // type
238 EXPECT_EQ('A', frame[3]);
239 EXPECT_EQ('C', frame[4]);
240 EXPECT_EQ('R', frame[5]);
241 EXPECT_EQ('O', frame[6]);
242 EXPECT_EQ('*', frame[7]);
243 EXPECT_EQ(0, frame[8]);
244 EXPECT_EQ(crfsCrc(frame, frameLen), frame[9]);
246 ENABLE_ARMING_FLAG(ARMED);
248 frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_FLIGHT_MODE);
249 EXPECT_EQ(5 + FRAME_HEADER_FOOTER_LEN, frameLen);
250 EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
251 EXPECT_EQ(7, frame[1]); // length
252 EXPECT_EQ(0x21, frame[2]); // type
253 EXPECT_EQ('A', frame[3]);
254 EXPECT_EQ('C', frame[4]);
255 EXPECT_EQ('R', frame[5]);
256 EXPECT_EQ('O', frame[6]);
257 EXPECT_EQ(0, frame[7]);
258 EXPECT_EQ(crfsCrc(frame, frameLen), frame[8]);
260 enableFlightMode(ANGLE_MODE);
261 EXPECT_EQ(ANGLE_MODE, FLIGHT_MODE(ANGLE_MODE));
262 frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_FLIGHT_MODE);
263 EXPECT_EQ(5 + FRAME_HEADER_FOOTER_LEN, frameLen);
264 EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
265 EXPECT_EQ(7, frame[1]); // length
266 EXPECT_EQ(0x21, frame[2]); // type
267 EXPECT_EQ('S', frame[3]);
268 EXPECT_EQ('T', frame[4]);
269 EXPECT_EQ('A', frame[5]);
270 EXPECT_EQ('B', frame[6]);
271 EXPECT_EQ(0, frame[7]);
272 EXPECT_EQ(crfsCrc(frame, frameLen), frame[8]);
274 disableFlightMode(ANGLE_MODE);
275 enableFlightMode(HORIZON_MODE);
276 EXPECT_EQ(HORIZON_MODE, FLIGHT_MODE(HORIZON_MODE));
277 frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_FLIGHT_MODE);
278 EXPECT_EQ(4 + FRAME_HEADER_FOOTER_LEN, frameLen);
279 EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
280 EXPECT_EQ(6, frame[1]); // length
281 EXPECT_EQ(0x21, frame[2]); // type
282 EXPECT_EQ('H', frame[3]);
283 EXPECT_EQ('O', frame[4]);
284 EXPECT_EQ('R', frame[5]);
285 EXPECT_EQ(0, frame[6]);
286 EXPECT_EQ(crfsCrc(frame, frameLen), frame[7]);
288 disableFlightMode(HORIZON_MODE);
289 airMode = true;
290 frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_FLIGHT_MODE);
291 EXPECT_EQ(4 + FRAME_HEADER_FOOTER_LEN, frameLen);
292 EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
293 EXPECT_EQ(6, frame[1]); // length
294 EXPECT_EQ(0x21, frame[2]); // type
295 EXPECT_EQ('A', frame[3]);
296 EXPECT_EQ('I', frame[4]);
297 EXPECT_EQ('R', frame[5]);
298 EXPECT_EQ(0, frame[6]);
299 EXPECT_EQ(crfsCrc(frame, frameLen), frame[7]);
302 // STUBS
304 extern "C" {
306 int16_t debug[DEBUG16_VALUE_COUNT];
308 const uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000, 400000}; // see baudRate_e
310 uint16_t batteryWarningVoltage;
311 uint8_t useHottAlarmSoundPeriod (void) { return 0; }
313 attitudeEulerAngles_t attitude = { { 0, 0, 0 } }; // absolute angle inclination in multiple of 0.1 degree 180 deg = 1800
315 uint16_t GPS_distanceToHome; // distance to home point in meters
316 gpsSolutionData_t gpsSol;
318 void beeperConfirmationBeeps(uint8_t beepCount) {UNUSED(beepCount);}
320 uint32_t micros(void) {return 0;}
321 uint32_t microsISR(void) {return micros();}
323 bool featureIsEnabled(uint32_t) {return true;}
325 uint32_t serialRxBytesWaiting(const serialPort_t *) {return 0;}
326 uint32_t serialTxBytesFree(const serialPort_t *) {return 0;}
327 uint8_t serialRead(serialPort_t *) {return 0;}
328 void serialWrite(serialPort_t *, uint8_t) {}
329 void serialWriteBuf(serialPort_t *, const uint8_t *, int) {}
330 void serialSetMode(serialPort_t *, portMode_e) {}
331 serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;}
332 void closeSerialPort(serialPort_t *) {}
333 bool isSerialTransmitBufferEmpty(const serialPort_t *) { return true; }
335 const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e) {return NULL;}
337 bool telemetryDetermineEnabledState(portSharing_e) {return true;}
338 bool telemetryCheckRxPortShared(const serialPortConfig_t *, SerialRXType) {return true;}
339 bool telemetryIsSensorEnabled(sensor_e) {return true;}
341 portSharing_e determinePortSharing(const serialPortConfig_t *, serialPortFunction_e) {return PORTSHARING_NOT_SHARED;}
343 bool airmodeIsEnabled(void) {return airMode;}
345 int32_t getAmperage(void)
347 return testAmperage;
350 uint16_t getBatteryVoltage(void)
352 return testBatteryVoltage;
355 uint16_t getLegacyBatteryVoltage(void)
357 return (testBatteryVoltage + 5) / 10;
360 uint16_t getBatteryAverageCellVoltage(void)
362 return 0;
365 batteryState_e getBatteryState(void)
367 return BATTERY_OK;
370 uint8_t calculateBatteryPercentageRemaining(void)
372 return 67;
375 int32_t getEstimatedAltitudeCm(void)
377 return gpsSol.llh.altCm; // function returns cm not m.
380 int32_t getMAhDrawn(void)
382 return testmAhDrawn;
385 bool sendMspReply(uint8_t, mspResponseFnPtr) { return false; }
386 bool handleMspFrame(uint8_t *, uint8_t, uint8_t *) { return false; }
387 bool isBatteryVoltageConfigured(void) { return true; }
388 bool isAmperageConfigured(void) { return true; }
389 timeUs_t rxFrameTimeUs(void) { return 0; }