1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-26 01:35:41 +03:00

ExpressLrs v2.0.0 support

This commit is contained in:
phobos- 2021-01-03 14:14:16 +01:00
parent 4c034d67ee
commit e00a3abc59
56 changed files with 6235 additions and 49 deletions

View file

@ -415,8 +415,37 @@ rx_spi_spektrum_unittest_SRC := \
$(USER_DIR)/rx/cyrf6936_spektrum.c
rx_spi_spektrum_unittest_DEFINES := \
USE_RX_SPI \
USE_RX_SPEKTRUM
USE_RX_SPI= \
USE_RX_SPEKTRUM=
rx_spi_expresslrs_unittest_SRC := \
$(USER_DIR)/pg/rx_spi_expresslrs.c \
$(USER_DIR)/rx/expresslrs_common.c \
$(USER_DIR)/rx/expresslrs.c \
rx_spi_expresslrs_unittest_DEFINES := \
USE_RX_SPI= \
USE_RX_EXPRESSLRS= \
USE_RX_SX1280= \
USE_RX_SX127X= \
rx_spi_expresslrs_telemetry_unittest_SRC := \
$(USER_DIR)/rx/crsf.c \
$(USER_DIR)/telemetry/crsf.c \
$(USER_DIR)/common/crc.c \
$(USER_DIR)/common/maths.c \
$(USER_DIR)/common/streambuf.c \
$(USER_DIR)/common/gps_conversion.c \
$(USER_DIR)/common/printf.c \
$(USER_DIR)/common/typeconversion.c \
$(USER_DIR)/rx/expresslrs_telemetry.c \
$(USER_DIR)/build/atomic.c \
$(USER_DIR)/telemetry/msp_shared.c \
rx_spi_expresslrs_telemetry_unittest_DEFINES := \
USE_RX_EXPRESSLRS= \
USE_GPS= \
USE_MSP_OVER_TELEMETRY= \
# Please tweak the following variable definitions as needed by your
# project, except GTEST_HEADERS, which you can use in your own targets

View file

@ -357,7 +357,7 @@ const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NU
bool telemetryCheckRxPortShared(const serialPortConfig_t *) {return false;}
serialPort_t *telemetrySharedPort = NULL;
void crsfScheduleDeviceInfoResponse(void) {};
void crsfScheduleMspResponse(void) {};
void crsfScheduleMspResponse(uint8_t ) {};
bool bufferMspFrame(uint8_t *, int) {return true;}
bool isBatteryVoltageAvailable(void) { return true; }
bool isAmperageAvailable(void) { return true; }

View file

@ -0,0 +1,466 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
/*
* Based on https://github.com/ExpressLRS/ExpressLRS
* Thanks to AlessandroAU, original creator of the ExpressLRS project.
*/
#include <stdint.h>
#include <stdbool.h>
#include <limits.h>
extern "C" {
#include "platform.h"
#include "build/version.h"
#include "common/printf.h"
#include "drivers/io.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "msp/msp.h"
#include "msp/msp_serial.h"
#include "telemetry/telemetry.h"
#include "telemetry/msp_shared.h"
#include "rx/crsf_protocol.h"
#include "rx/expresslrs_telemetry.h"
#include "flight/imu.h"
#include "sensors/battery.h"
#include "sensors/sensors.h"
#include "sensors/acceleration.h"
#include "config/config.h"
#include "io/gps.h"
#include "msp/msp_protocol.h"
extern uint8_t tlmSensors;
extern uint8_t currentPayloadIndex;
extern volatile bool mspReplyPending;
extern volatile bool deviceInfoReplyPending;
bool airMode;
uint16_t testBatteryVoltage = 0;
int32_t testAmperage = 0;
int32_t testmAhDrawn = 0;
PG_REGISTER(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 0);
PG_REGISTER(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 0);
}
#include "unittest_macros.h"
#include "gtest/gtest.h"
//make clean test_rx_spi_expresslrs_telemetry_unittest
TEST(RxSpiExpressLrsTelemetryUnitTest, TestInit)
{
initTelemetry();
EXPECT_EQ(tlmSensors, 15);
}
static void testSetDataToTransmit(uint8_t payloadSize, uint8_t *payload)
{
uint8_t *data;
uint8_t maxLength;
uint8_t packageIndex;
bool confirmValue = true;
setTelemetryDataToTransmit(payloadSize, payload, ELRS_TELEMETRY_BYTES_PER_CALL);
for (int j = 0; j < (1 + ((payloadSize - 1) / ELRS_TELEMETRY_BYTES_PER_CALL)); j++) {
getCurrentTelemetryPayload(&packageIndex, &maxLength, &data);
EXPECT_LE(maxLength, 5);
EXPECT_EQ(1 + j, packageIndex);
for(int i = 0; i < maxLength; i++) {
EXPECT_EQ(payload[i + j * ELRS_TELEMETRY_BYTES_PER_CALL], data[i]);
}
confirmCurrentTelemetryPayload(confirmValue);
confirmValue = !confirmValue;
}
getCurrentTelemetryPayload(&packageIndex, &maxLength, &data);
EXPECT_EQ(0, packageIndex);
EXPECT_EQ(true, isTelemetrySenderActive());
confirmCurrentTelemetryPayload(!confirmValue);
EXPECT_EQ(true, isTelemetrySenderActive());
confirmCurrentTelemetryPayload(confirmValue);
EXPECT_EQ(false, isTelemetrySenderActive());
}
TEST(RxSpiExpressLrsTelemetryUnitTest, TestGps)
{
initTelemetry();
currentPayloadIndex = 0;
gpsSol.llh.lat = 56 * GPS_DEGREES_DIVIDER;
gpsSol.llh.lon = 163 * GPS_DEGREES_DIVIDER;
gpsSol.llh.altCm = 2345 * 100; // altitude in cm / 100 + 1000m offset, so CRSF value should be 3345
gpsSol.groundSpeed = 1630; // speed in cm/s, 16.3 m/s = 58.68 km/h, so CRSF (km/h *10) value is 587
gpsSol.numSat = 9;
gpsSol.groundCourse = 1479; // degrees * 10
uint8_t *payload = 0;
uint8_t payloadSize = 0;
getNextTelemetryPayload(&payloadSize, &payload);
EXPECT_EQ(currentPayloadIndex, 1);
int32_t lattitude = payload[3] << 24 | payload[4] << 16 | payload[5] << 8 | payload[6];
EXPECT_EQ(560000000, lattitude);
int32_t longitude = payload[7] << 24 | payload[8] << 16 | payload[9] << 8 | payload[10];
EXPECT_EQ(1630000000, longitude);
uint16_t groundSpeed = payload[11] << 8 | payload[12];
EXPECT_EQ(587, groundSpeed);
uint16_t GPSheading = payload[13] << 8 | payload[14];
EXPECT_EQ(14790, GPSheading);
uint16_t altitude = payload[15] << 8 | payload[16];
EXPECT_EQ(3345, altitude);
uint8_t satelliteCount = payload[17];
EXPECT_EQ(9, satelliteCount);
testSetDataToTransmit(payloadSize, payload);
}
TEST(RxSpiExpressLrsTelemetryUnitTest, TestBattery)
{
initTelemetry();
currentPayloadIndex = 1;
testBatteryVoltage = 330; // 3.3V = 3300 mv
testAmperage = 2960; // = 29.60A = 29600mA - amperage is in 0.01A steps
testmAhDrawn = 1234;
uint8_t *payload = 0;
uint8_t payloadSize = 0;
getNextTelemetryPayload(&payloadSize, &payload);
EXPECT_EQ(currentPayloadIndex, 2);
uint16_t voltage = payload[3] << 8 | payload[4]; // mV * 100
EXPECT_EQ(33, voltage);
uint16_t current = payload[5] << 8 | payload[6]; // mA * 100
EXPECT_EQ(296, current);
uint32_t capacity = payload[7] << 16 | payload[8] << 8 | payload[9]; // mAh
EXPECT_EQ(1234, capacity);
uint16_t remaining = payload[10]; // percent
EXPECT_EQ(67, remaining);
testSetDataToTransmit(payloadSize, payload);
}
TEST(RxSpiExpressLrsTelemetryUnitTest, TestAttitude)
{
initTelemetry();
currentPayloadIndex = 2;
attitude.values.pitch = 678; // decidegrees == 1.183333232852155 rad
attitude.values.roll = 1495; // 2.609267231731523 rad
attitude.values.yaw = -1799; //3.139847324337799 rad
uint8_t *payload = 0;
uint8_t payloadSize = 0;
getNextTelemetryPayload(&payloadSize, &payload);
EXPECT_EQ(currentPayloadIndex, 3);
int16_t pitch = payload[3] << 8 | payload[4]; // rad / 10000
EXPECT_EQ(11833, pitch);
int16_t roll = payload[5] << 8 | payload[6];
EXPECT_EQ(26092, roll);
int16_t yaw = payload[7] << 8 | payload[8];
EXPECT_EQ(-31398, yaw);
testSetDataToTransmit(payloadSize, payload);
}
TEST(RxSpiExpressLrsTelemetryUnitTest, TestFlightMode)
{
initTelemetry();
currentPayloadIndex = 3;
airMode = false;
uint8_t *payload = 0;
uint8_t payloadSize = 0;
getNextTelemetryPayload(&payloadSize, &payload);
EXPECT_EQ(currentPayloadIndex, 0);
EXPECT_EQ('W', payload[3]);
EXPECT_EQ('A', payload[4]);
EXPECT_EQ('I', payload[5]);
EXPECT_EQ('T', payload[6]);
EXPECT_EQ('*', payload[7]);
EXPECT_EQ(0, payload[8]);
testSetDataToTransmit(payloadSize, payload);
}
TEST(RxSpiExpressLrsTelemetryUnitTest, TestMspVersionRequest)
{
uint8_t request[15] = {238,12,122,200,234,48,0,1,1,0,0,0,0,128, 0};
uint8_t response[12] = {200,10,123,234,200,48,3,1,0,1,44,42};
uint8_t data1[6] = {1, request[0], request[1], request[2], request[3], request[4]};
uint8_t data2[6] = {2, request[5], request[6], request[7], request[8], request[9]};
uint8_t data3[6] = {3, request[10], request[11], request[12], request[13], request[14]};
uint8_t mspBuffer[15] = {0};
uint8_t *payload = 0;
uint8_t payloadSize = 0;
EXPECT_EQ(CRSF_ADDRESS_CRSF_TRANSMITTER, request[0]);
EXPECT_EQ(CRSF_FRAMETYPE_MSP_REQ, request[2]);
EXPECT_EQ(CRSF_ADDRESS_FLIGHT_CONTROLLER, request[3]);
EXPECT_EQ(CRSF_ADDRESS_RADIO_TRANSMITTER, request[4]);
initTelemetry();
initSharedMsp();
setMspDataToReceive(15, mspBuffer, ELRS_MSP_BYTES_PER_CALL);
receiveMspData(data1[0], data1 + 1);
receiveMspData(data2[0], data2 + 1);
receiveMspData(data3[0], data3 + 1);
EXPECT_FALSE(hasFinishedMspData());
receiveMspData(0, 0);
EXPECT_TRUE(hasFinishedMspData());
processMspPacket(mspBuffer);
EXPECT_TRUE(mspReplyPending);
getNextTelemetryPayload(&payloadSize, &payload);
EXPECT_EQ(payload[1] + 2, payloadSize);
EXPECT_EQ(CRSF_FRAMETYPE_MSP_RESP, payload[2]);
EXPECT_EQ(CRSF_ADDRESS_RADIO_TRANSMITTER, payload[3]);
EXPECT_EQ(CRSF_ADDRESS_FLIGHT_CONTROLLER, payload[4]);
for (int i = 0; i < 12; i++) {
EXPECT_EQ(response[i], payload[i]);
}
testSetDataToTransmit(payloadSize, payload);
}
TEST(RxSpiExpressLrsTelemetryUnitTest, TestMspPidRequest)
{
uint8_t pidRequest[15] = {0x00,0x0D,0x7A,0xC8,0xEA,0x30,0x00,0x70,0x70,0x00,0x00,0x00,0x00,0x69, 0x00};
uint8_t data1[6] = {1, pidRequest[0], pidRequest[1], pidRequest[2], pidRequest[3], pidRequest[4]};
uint8_t data2[6] = {2, pidRequest[5], pidRequest[6], pidRequest[7], pidRequest[8], pidRequest[9]};
uint8_t data3[6] = {3, pidRequest[10], pidRequest[11], pidRequest[12], pidRequest[13], pidRequest[14]};
uint8_t mspBuffer[15] = {0};
uint8_t *payload = 0;
uint8_t payloadSize = 0;
initTelemetry();
initSharedMsp();
setMspDataToReceive(sizeof(mspBuffer), mspBuffer, ELRS_MSP_BYTES_PER_CALL);
receiveMspData(data1[0], data1 + 1);
EXPECT_FALSE(hasFinishedMspData());
receiveMspData(data2[0], data2 + 1);
EXPECT_FALSE(hasFinishedMspData());
receiveMspData(data3[0], data3 + 1);
EXPECT_FALSE(hasFinishedMspData());
receiveMspData(0, 0);
EXPECT_TRUE(hasFinishedMspData());
for (int i = 0; i < 15; i ++) {
EXPECT_EQ(mspBuffer[i], pidRequest[i]);
}
EXPECT_FALSE(mspReplyPending);
processMspPacket(mspBuffer);
EXPECT_TRUE(mspReplyPending);
getNextTelemetryPayload(&payloadSize, &payload);
EXPECT_FALSE(mspReplyPending);
EXPECT_EQ(payloadSize, payload[1] + 2);
EXPECT_EQ(CRSF_FRAMETYPE_MSP_RESP, payload[2]);
EXPECT_EQ(CRSF_ADDRESS_RADIO_TRANSMITTER, payload[3]);
EXPECT_EQ(CRSF_ADDRESS_FLIGHT_CONTROLLER, payload[4]);
EXPECT_EQ(0x31, payload[5]); //0x30 + 1 since it is second request, see msp_shared.c:L204
EXPECT_EQ(0x1E, payload[6]);
EXPECT_EQ(0x70, payload[7]);
for (int i = 1; i <= 30; i++) {
EXPECT_EQ(i, payload[i + 7]);
}
EXPECT_EQ(0x1E, payload[37]);
testSetDataToTransmit(payloadSize, payload);
}
TEST(RxSpiExpressLrsTelemetryUnitTest, TestMspVtxRequest)
{
uint8_t vtxRequest[15] = {0x00,0x0C,0x7C,0xC8,0xEA,0x30,0x04,0x59,0x18,0x00,0x01,0x00,0x44,0x5E, 0x00};
uint8_t data1[6] = {1, vtxRequest[0], vtxRequest[1], vtxRequest[2], vtxRequest[3], vtxRequest[4]};
uint8_t data2[6] = {2, vtxRequest[5], vtxRequest[6], vtxRequest[7], vtxRequest[8], vtxRequest[9]};
uint8_t data3[6] = {3, vtxRequest[10], vtxRequest[11], vtxRequest[12], vtxRequest[13], vtxRequest[14]};
uint8_t mspBuffer[15] = {0};
uint8_t *payload = 0;
uint8_t payloadSize = 0;
initTelemetry();
initSharedMsp();
setMspDataToReceive(sizeof(mspBuffer), mspBuffer, ELRS_MSP_BYTES_PER_CALL);
receiveMspData(data1[0], data1 + 1);
receiveMspData(data2[0], data2 + 1);
receiveMspData(data3[0], data3 + 1);
EXPECT_FALSE(hasFinishedMspData());
receiveMspData(0, 0);
EXPECT_TRUE(hasFinishedMspData());
processMspPacket(mspBuffer);
EXPECT_TRUE(mspReplyPending);
getNextTelemetryPayload(&payloadSize, &payload);
EXPECT_EQ(payloadSize, payload[1] + 2);
EXPECT_EQ(CRSF_FRAMETYPE_MSP_RESP, payload[2]);
EXPECT_EQ(CRSF_ADDRESS_RADIO_TRANSMITTER, payload[3]);
EXPECT_EQ(CRSF_ADDRESS_FLIGHT_CONTROLLER, payload[4]);
EXPECT_EQ(0x32, payload[5]); //0x30 + 2 since it is third request, see msp_shared.c:L204
EXPECT_EQ(0x00, payload[6]);
EXPECT_EQ(0x59, payload[7]);
testSetDataToTransmit(payloadSize, payload);
}
TEST(RxSpiExpressLrsTelemetryUnitTest, TestDeviceInfoResp)
{
uint8_t mspBuffer[15] = {0};
uint8_t *payload = 0;
uint8_t payloadSize = 0;
uint8_t pingData[4] = {1, CRSF_ADDRESS_CRSF_TRANSMITTER, 1, CRSF_FRAMETYPE_DEVICE_PING};
initTelemetry();
initSharedMsp();
setMspDataToReceive(sizeof(mspBuffer), mspBuffer, ELRS_MSP_BYTES_PER_CALL);
receiveMspData(pingData[0], pingData + 1);
EXPECT_FALSE(hasFinishedMspData());
receiveMspData(0, 0);
EXPECT_TRUE(hasFinishedMspData());
EXPECT_FALSE(deviceInfoReplyPending);
processMspPacket(mspBuffer);
EXPECT_TRUE(deviceInfoReplyPending);
getNextTelemetryPayload(&payloadSize, &payload);
EXPECT_FALSE(deviceInfoReplyPending);
EXPECT_EQ(CRSF_FRAMETYPE_DEVICE_INFO, payload[2]);
EXPECT_EQ(CRSF_ADDRESS_RADIO_TRANSMITTER, payload[3]);
EXPECT_EQ(CRSF_ADDRESS_FLIGHT_CONTROLLER, payload[4]);
EXPECT_EQ(0x01, payload[payloadSize - 2]);
EXPECT_EQ(0, payload[payloadSize - 3]);
testSetDataToTransmit(payloadSize, payload);
}
// STUBS
extern "C" {
attitudeEulerAngles_t attitude = { { 0, 0, 0 } }; // absolute angle inclination in multiple of 0.1 degree 180 deg = 1800
gpsSolutionData_t gpsSol;
rssiSource_e rssiSource;
uint8_t armingFlags;
uint8_t stateFlags;
uint16_t flightModeFlags;
uint32_t microsISR(void) {return 0; }
void beeperConfirmationBeeps(uint8_t ) {}
uint8_t calculateBatteryPercentageRemaining(void) {return 67; }
int32_t getAmperage(void) {return testAmperage; }
uint16_t getBatteryVoltage(void) {return testBatteryVoltage; }
uint16_t getLegacyBatteryVoltage(void) {return (testBatteryVoltage + 5) / 10; }
uint16_t getBatteryAverageCellVoltage(void) {return 0; }
batteryState_e getBatteryState(void) {return BATTERY_OK; }
bool featureIsEnabled(uint32_t) {return true; }
bool telemetryIsSensorEnabled(sensor_e) {return true; }
bool sensors(uint32_t ) { return true; }
bool airmodeIsEnabled(void) {return airMode; }
bool isBatteryVoltageConfigured(void) { return true; }
bool isAmperageConfigured(void) { return true; }
const serialPortConfig_t *findSerialPortConfig(serialPortFunction_e) { return NULL;}
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) { return NULL; }
void serialWriteBuf(serialPort_t *, const uint8_t *, int) {}
int32_t getEstimatedAltitudeCm(void) { return gpsSol.llh.altCm; }
int32_t getMAhDrawn(void) { return testmAhDrawn; }
bool isArmingDisabled(void) { return false; }
mspDescriptor_t mspDescriptorAlloc(void) {return 0; }
uint8_t mspSerialOutBuf[MSP_PORT_OUTBUF_SIZE];
mspResult_e mspFcProcessCommand(mspDescriptor_t srcDesc, mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn) {
UNUSED(srcDesc);
UNUSED(mspPostProcessFn);
sbuf_t *dst = &reply->buf;
const uint8_t cmdMSP = cmd->cmd;
reply->cmd = cmd->cmd;
if (cmdMSP == 0x70) {
for (unsigned int ii=1; ii<=30; ii++) {
sbufWriteU8(dst, ii);
}
} else if (cmdMSP == 0xCA) {
return MSP_RESULT_ACK;
} else if (cmdMSP == 0x01) {
sbufWriteU8(dst, MSP_PROTOCOL_VERSION);
sbufWriteU8(dst, API_VERSION_MAJOR);
sbufWriteU8(dst, API_VERSION_MINOR);
}
return MSP_RESULT_ACK;
}
timeUs_t rxFrameTimeUs(void) { return 0; }
}

View file

@ -0,0 +1,470 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
/*
* Based on https://github.com/ExpressLRS/ExpressLRS
* Thanks to AlessandroAU, original creator of the ExpressLRS project.
*/
#include <stdint.h>
#include <stdbool.h>
#include <limits.h>
extern "C" {
#include "platform.h"
#include "drivers/io.h"
#include "common/filter.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx_spi.h"
#include "pg/rx_spi_expresslrs.h"
#include "rx/rx_spi.h"
#include "rx/expresslrs.h"
#include "rx/expresslrs_impl.h"
#include "drivers/rx/rx_sx127x.h"
#include "drivers/rx/rx_sx1280.h"
extern uint8_t FHSSsequence[ELRS_NR_SEQUENCE_ENTRIES];
extern uint16_t crc14tab[ELRS_CRC_LEN];
extern elrsReceiver_t receiver;
static const elrsReceiver_t empty = elrsReceiver_t();
static rxRuntimeState_t config = rxRuntimeState_t();
static rxSpiExtiConfig_t extiConfig;
static const rxSpiConfig_t injectedConfig = {
.extiIoTag = IO_TAG(PA0),
};
}
#include "unittest_macros.h"
#include "gtest/gtest.h"
//make clean test_rx_spi_expresslrs_unittest
TEST(RxSpiExpressLrsUnitTest, TestCrc14)
{
uint16_t expectedCrc14Tab[ELRS_CRC_LEN] = {
0,28247,62201,40110,52133,42482,14684,22283,
38730,63773,26035,3044,23791,12984,44566,49217,
11924,16579,56429,45626,58673,35686,6088,31135,
47582,55177,19239,9584,29307,7212,32898,61141,
29567,7464,33158,61393,47322,54925,18979,9332,
58421,35426,5836,30875,12176,16839,56681,45886,
24043,13244,44818,49477,38478,63513,25783,2784,
51873,42230,14424,22031,260,28499,62461,40362,
51369,42750,14928,21511,780,27995,61941,40866,
24547,12724,44314,49997,37958,64017,26303,2280,
58941,34922,5316,31379,11672,17359,57185,45366,
29047,7968,33678,60889,47826,54405,18475,9852,
48086,54657,18735,10104,28787,7716,33418,60637,
11420,17099,56933,45106,59193,35182,5568,31639,
38210,64277,26555,2540,24295,12464,44062,49737,
520,27743,61681,40614,51629,43002,15188,21763,
37202,65285,25515,3580,23287,13472,43022,50777,
1560,26703,62689,39606,52669,41962,16196,20755,
49094,53649,19775,9064,29795,6708,34458,59597,
10380,18139,55925,46114,58153,36222,4560,32647,
57901,35962,4308,32387,10632,18399,56177,46374,
30055,6960,34718,59849,48834,53397,19515,8812,
52409,41710,15936,20503,1820,26955,62949,39858,
23539,13732,43274,51037,36950,65025,25263,3320,
23035,14252,43778,50517,37470,64521,24743,3824,
52913,41190,15432,21023,1300,27459,63469,39354,
30575,6456,34198,60353,48330,53917,20019,8292,
57381,36466,4828,31883,11136,17879,55673,46894,
10884,17619,55421,46634,57633,36726,5080,32143,
48590,54169,20279,8544,30315,6204,33938,60101,
1040,27207,63209,39102,53173,41442,15692,21275,
37722,64781,24995,4084,22783,13992,43526,50257
};
generateCrc14Table();
for (int i = 0; i < ELRS_CRC_LEN; i++) {
EXPECT_EQ(expectedCrc14Tab[i], crc14tab[i]);
}
}
TEST(RxSpiExpressLrsUnitTest, TestFHSSTable)
{
const uint8_t UID[6] = {1, 2, 3, 4, 5, 6};
const uint8_t expectedSequence[2][ELRS_NR_SEQUENCE_ENTRIES] = {
{
40, 43, 39, 18, 52, 19, 36, 7, 1, 12,
71, 5, 42, 46, 50, 28, 49, 33, 76, 51,
60, 70, 47, 61, 0, 55, 72, 37, 53, 25,
3, 11, 41, 13, 35, 27, 9, 75, 48, 77,
73, 74, 69, 58, 14, 31, 10, 59, 66, 4,
78, 17, 44, 54, 29, 57, 21, 64, 22, 67,
62, 56, 15, 79, 6, 34, 23, 30, 32, 2,
68, 8, 63, 65, 45, 20, 24, 26, 16, 38,
40, 8, 52, 29, 57, 10, 6, 26, 19, 75,
21, 24, 1, 9, 50, 32, 69, 67, 2, 59,
28, 48, 77, 60, 41, 49, 68, 4, 5, 3,
44, 78, 58, 31, 16, 62, 35, 45, 73, 11,
33, 46, 42, 36, 64, 7, 34, 53, 17, 25,
37, 38, 54, 55, 15, 76, 18, 43, 23, 12,
39, 51, 22, 79, 74, 63, 27, 66, 65, 47,
70, 0, 30, 61, 13, 56, 14, 72, 71, 20,
40, 71, 68, 12, 57, 45, 10, 53, 21, 15,
69, 26, 54, 55, 73, 47, 35, 77, 1, 31,
20, 0, 38, 76, 5, 60, 6, 79, 3, 16,
50, 17, 52, 62, 18, 46, 28, 39, 29, 51,
43, 34, 49, 56, 32, 61, 74, 58, 25, 44,
2, 19, 65, 4, 13, 67, 11, 30, 66, 64,
36, 24, 75, 33, 59, 7, 41, 70, 48, 14,
42, 37, 8, 23, 78, 63, 22, 9, 72, 27
},
{
20, 37, 1, 3, 7, 26, 36, 29, 15, 35,
33, 24, 10, 34, 13, 31, 22, 9, 28, 23,
17, 38, 6, 27, 0, 32, 11, 5, 18, 25,
2, 4, 12, 19, 16, 8, 30, 14, 21, 39,
20, 2, 14, 7, 13, 33, 32, 28, 21, 11,
25, 17, 22, 9, 3, 4, 0, 31, 35, 38,
10, 34, 26, 39, 36, 6, 19, 16, 30, 27,
15, 24, 18, 1, 23, 37, 29, 8, 12, 5,
20, 19, 24, 29, 27, 2, 22, 14, 0, 3,
23, 13, 12, 35, 4, 25, 38, 18, 33, 36,
21, 16, 5, 31, 9, 32, 11, 1, 6, 7,
10, 15, 26, 34, 39, 37, 28, 17, 30, 8,
20, 7, 4, 24, 19, 16, 8, 13, 15, 10,
14, 36, 34, 0, 17, 12, 28, 21, 39, 22,
3, 2, 32, 33, 27, 6, 37, 18, 31, 38,
23, 25, 26, 30, 9, 1, 35, 5, 11, 29,
20, 1, 35, 22, 0, 10, 11, 27, 18, 37,
21, 31, 9, 19, 30, 17, 5, 38, 29, 36,
3, 2, 25, 34, 23, 6, 15, 4, 16, 26,
12, 24, 14, 13, 39, 8, 32, 7, 28, 33,
20, 36, 13, 5, 39, 37, 15, 8, 9, 4,
22, 12, 1, 6, 32, 25, 17, 18, 27, 28,
23, 19, 26, 3, 38, 16, 2, 34, 14, 30,
10, 11, 7, 0, 35, 24, 21, 33, 31, 29
}
};
FHSSrandomiseFHSSsequence(UID, ISM2400);
for (int i = 0; i < ELRS_NR_SEQUENCE_ENTRIES; i++) {
EXPECT_EQ(expectedSequence[0][i], FHSSsequence[i]);
}
FHSSrandomiseFHSSsequence(UID, FCC915);
for (int i = 0; i < ELRS_NR_SEQUENCE_ENTRIES; i++) {
EXPECT_EQ(expectedSequence[1][i], FHSSsequence[i]);
}
}
TEST(RxSpiExpressLrsUnitTest, TestInitUnbound)
{
const uint8_t bindUID[6] = {0, 1, 2, 3, 4, 5};
receiver = empty;
expressLrsSpiInit(&injectedConfig, &config, &extiConfig);
//check initialization of elrsReceiver_t
EXPECT_TRUE(receiver.inBindingMode);
EXPECT_EQ(IO_NONE, receiver.resetPin);
EXPECT_EQ(IO_NONE, receiver.busyPin);
for (int i = 0; i < 6; i++) {
EXPECT_EQ(bindUID[i], receiver.UID[i]);
}
EXPECT_EQ(0, receiver.nonceRX);
EXPECT_EQ(0, receiver.freqOffset);
EXPECT_EQ(0, receiver.lastValidPacketMs);
const uint32_t initialFrequencies[7] = {
FREQ_HZ_TO_REG_VAL_900(433920000),
FREQ_HZ_TO_REG_VAL_900(921500000),
FREQ_HZ_TO_REG_VAL_900(433925000),
FREQ_HZ_TO_REG_VAL_900(866425000),
FREQ_HZ_TO_REG_VAL_900(866425000),
FREQ_HZ_TO_REG_VAL_900(915500000),
FREQ_HZ_TO_REG_VAL_24(2440400000)
};
for (int i = 0; i < 7; i++) {
receiver = empty;
rxExpressLrsSpiConfigMutable()->domain = i;
expressLrsSpiInit(&injectedConfig, &config, &extiConfig);
EXPECT_EQ(initialFrequencies[i], receiver.currentFreq);
}
// for unbound we need to initialize in 50HZ mode
receiver = empty;
rxExpressLrsSpiConfigMutable()->rateIndex = 1;
rxExpressLrsSpiConfigMutable()->domain = FCC915;
expressLrsSpiInit(&injectedConfig, &config, &extiConfig);
EXPECT_EQ(airRateConfig[0][2].index, receiver.modParams->index);
EXPECT_EQ(airRateConfig[0][2].enumRate, receiver.modParams->enumRate);
EXPECT_EQ(airRateConfig[0][2].bw, receiver.modParams->bw);
EXPECT_EQ(airRateConfig[0][2].sf, receiver.modParams->sf);
EXPECT_EQ(airRateConfig[0][2].cr, receiver.modParams->cr);
EXPECT_EQ(airRateConfig[0][2].interval, receiver.modParams->interval);
EXPECT_EQ(airRateConfig[0][2].tlmInterval, receiver.modParams->tlmInterval);
EXPECT_EQ(airRateConfig[0][2].fhssHopInterval, receiver.modParams->fhssHopInterval);
EXPECT_EQ(airRateConfig[0][2].preambleLen, receiver.modParams->preambleLen);
receiver = empty;
rxExpressLrsSpiConfigMutable()->rateIndex = 1;
rxExpressLrsSpiConfigMutable()->domain = ISM2400;
expressLrsSpiInit(&injectedConfig, &config, &extiConfig);
EXPECT_EQ(airRateConfig[1][3].index, receiver.modParams->index);
EXPECT_EQ(airRateConfig[1][3].enumRate, receiver.modParams->enumRate);
EXPECT_EQ(airRateConfig[1][3].bw, receiver.modParams->bw);
EXPECT_EQ(airRateConfig[1][3].sf, receiver.modParams->sf);
EXPECT_EQ(airRateConfig[1][3].cr, receiver.modParams->cr);
EXPECT_EQ(airRateConfig[1][3].interval, receiver.modParams->interval);
EXPECT_EQ(airRateConfig[1][3].tlmInterval, receiver.modParams->tlmInterval);
EXPECT_EQ(airRateConfig[1][3].fhssHopInterval, receiver.modParams->fhssHopInterval);
EXPECT_EQ(airRateConfig[1][3].preambleLen, receiver.modParams->preambleLen);
//check switch mode
receiver = empty;
rxExpressLrsSpiConfigMutable()->switchMode = SM_HYBRID;
expressLrsSpiInit(&injectedConfig, &config, &extiConfig);
EXPECT_EQ(16, config.channelCount);
receiver = empty;
rxExpressLrsSpiConfigMutable()->switchMode = SM_HYBRID_WIDE;
expressLrsSpiInit(&injectedConfig, &config, &extiConfig);
EXPECT_EQ(16, config.channelCount);
}
TEST(RxSpiExpressLrsUnitTest, TestInitBound)
{
const uint8_t validUID[6] = {0, 0, 1, 2, 3, 4};
receiver = empty;
memcpy(rxExpressLrsSpiConfigMutable()->UID, validUID, 6);
// check mod params
for (int i = 0; i < ELRS_RATE_MAX; i++) {
receiver = empty;
rxExpressLrsSpiConfigMutable()->rateIndex = i;
rxExpressLrsSpiConfigMutable()->domain = FCC915;
expressLrsSpiInit(&injectedConfig, &config, &extiConfig);
EXPECT_EQ(airRateConfig[0][i].index, receiver.modParams->index);
EXPECT_EQ(airRateConfig[0][i].enumRate, receiver.modParams->enumRate);
EXPECT_EQ(airRateConfig[0][i].bw, receiver.modParams->bw);
EXPECT_EQ(airRateConfig[0][i].sf, receiver.modParams->sf);
EXPECT_EQ(airRateConfig[0][i].cr, receiver.modParams->cr);
EXPECT_EQ(airRateConfig[0][i].interval, receiver.modParams->interval);
EXPECT_EQ(airRateConfig[0][i].tlmInterval, receiver.modParams->tlmInterval);
EXPECT_EQ(airRateConfig[0][i].fhssHopInterval, receiver.modParams->fhssHopInterval);
EXPECT_EQ(airRateConfig[0][i].preambleLen, receiver.modParams->preambleLen);
receiver = empty;
rxExpressLrsSpiConfigMutable()->rateIndex = i;
rxExpressLrsSpiConfigMutable()->domain = ISM2400;
expressLrsSpiInit(&injectedConfig, &config, &extiConfig);
EXPECT_EQ(airRateConfig[1][i].index, receiver.modParams->index);
EXPECT_EQ(airRateConfig[1][i].enumRate, receiver.modParams->enumRate);
EXPECT_EQ(airRateConfig[1][i].bw, receiver.modParams->bw);
EXPECT_EQ(airRateConfig[1][i].sf, receiver.modParams->sf);
EXPECT_EQ(airRateConfig[1][i].cr, receiver.modParams->cr);
EXPECT_EQ(airRateConfig[1][i].interval, receiver.modParams->interval);
EXPECT_EQ(airRateConfig[1][i].tlmInterval, receiver.modParams->tlmInterval);
EXPECT_EQ(airRateConfig[1][i].fhssHopInterval, receiver.modParams->fhssHopInterval);
EXPECT_EQ(airRateConfig[1][i].preambleLen, receiver.modParams->preambleLen);
}
expressLrsSpiInit(&injectedConfig, &config, &extiConfig);
EXPECT_FALSE(receiver.inBindingMode);
for (int i = 0; i < 6; i++) {
EXPECT_EQ(validUID[i], receiver.UID[i]);
}
}
TEST(RxSpiExpressLrsUnitTest, TestLQCalc)
{
lqReset();
for (int i = 1; i <= 100; i++) {
lqNewPeriod();
lqIncrease();
EXPECT_EQ(i, lqGet());
}
lqNewPeriod();
lqIncrease();
EXPECT_EQ(100, lqGet());
for (int i = 99; i >= 0; i--) {
lqNewPeriod();
EXPECT_EQ(i, lqGet());
}
lqNewPeriod();
EXPECT_EQ(0, lqGet());
lqReset();
lqNewPeriod();
EXPECT_EQ(0, lqGet());
lqIncrease();
EXPECT_EQ(1, lqGet());
}
TEST(RxSpiExpressLrsUnitTest, Test1bSwitchDecode)
{
EXPECT_EQ(1000, convertSwitch1b(0));
EXPECT_EQ(2000, convertSwitch1b(1));
EXPECT_EQ(2000, convertSwitch1b(2));
EXPECT_EQ(2000, convertSwitch1b(255));
}
TEST(RxSpiExpressLrsUnitTest, Test3bSwitchDecode)
{
EXPECT_EQ(1000, convertSwitch3b(0));
EXPECT_EQ(1275, convertSwitch3b(1));
EXPECT_EQ(1425, convertSwitch3b(2));
EXPECT_EQ(1575, convertSwitch3b(3));
EXPECT_EQ(1725, convertSwitch3b(4));
EXPECT_EQ(2000, convertSwitch3b(5));
EXPECT_EQ(1500, convertSwitch3b(6));
EXPECT_EQ(1500, convertSwitch3b(7));
EXPECT_EQ(1500, convertSwitch3b(8));
EXPECT_EQ(1500, convertSwitch3b(123));
EXPECT_EQ(1500, convertSwitch3b(255));
}
TEST(RxSpiExpressLrsUnitTest, Test4bSwitchDecode)
{
EXPECT_EQ(1000, convertSwitchNb(0, 15));
EXPECT_EQ(1066, convertSwitchNb(1, 15));
EXPECT_EQ(1133, convertSwitchNb(2, 15));
EXPECT_EQ(1200, convertSwitchNb(3, 15));
EXPECT_EQ(1266, convertSwitchNb(4, 15));
EXPECT_EQ(1333, convertSwitchNb(5, 15));
EXPECT_EQ(1400, convertSwitchNb(6, 15));
EXPECT_EQ(1466, convertSwitchNb(7, 15));
EXPECT_EQ(1533, convertSwitchNb(8, 15));
EXPECT_EQ(1600, convertSwitchNb(9, 15));
EXPECT_EQ(1666, convertSwitchNb(10, 15));
EXPECT_EQ(1733, convertSwitchNb(11, 15));
EXPECT_EQ(1800, convertSwitchNb(12, 15));
EXPECT_EQ(1866, convertSwitchNb(13, 15));
EXPECT_EQ(1933, convertSwitchNb(14, 15));
EXPECT_EQ(2000, convertSwitchNb(15, 15));
EXPECT_EQ(1500, convertSwitchNb(16, 15));
EXPECT_EQ(1500, convertSwitchNb(255, 15));
}
TEST(RxSpiExpressLrsUnitTest, TestAnalogDecode)
{
EXPECT_EQ(988, convertAnalog(172));
EXPECT_EQ(1500, convertAnalog(992));
EXPECT_EQ(2012, convertAnalog(1811));
}
// STUBS
extern "C" {
int16_t *debug;
uint8_t debugMode;
rssiSource_e rssiSource;
linkQualitySource_e linkQualitySource;
void setRssi(uint16_t , rssiSource_e ) {}
void setRssiDirect(uint16_t , rssiSource_e ) {}
uint32_t micros(void) { return 0; }
uint32_t millis(void) { return 0; }
bool IORead(IO_t ) { return true; }
IO_t IOGetByTag(ioTag_t ) { return (IO_t)1; }
void IOHi(IO_t ) {}
void IOLo(IO_t ) {}
void writeEEPROM(void) {}
void rxSpiCommonIOInit(const rxSpiConfig_t *) {}
void rxSpiLedBlinkRxLoss(rx_spi_received_e ) {}
void rxSpiLedBlinkBind(void) {}
bool rxSpiCheckBindRequested(bool)
{
return false;
}
bool rxSpiExtiConfigured(void) { return true; }
bool sx1280IsBusy(void) { return false; }
void sx1280Config(const sx1280LoraBandwidths_e , const sx1280LoraSpreadingFactors_e , const sx1280LoraCodingRates_e , const uint32_t , const uint8_t , const bool ) {}
void sx1280StartReceiving(void) {}
uint8_t sx1280ISR(uint32_t *timestamp)
{
*timestamp = 0;
return 0;
}
void sx1280TransmitData(const uint8_t *, const uint8_t ) {}
void sx1280ReceiveData(uint8_t *, const uint8_t ) {}
void sx1280SetFrequencyReg(const uint32_t ) {}
void sx1280GetLastPacketStats(int8_t *rssi, int8_t *snr)
{
*rssi = 0;
*snr = 0;
}
void sx1280AdjustFrequency(int32_t , const uint32_t ) {}
bool sx1280Init(IO_t , IO_t ) { return true; }
void sx127xConfig(const sx127xBandwidth_e , const sx127xSpreadingFactor_e , const sx127xCodingRate_e , const uint32_t , const uint8_t , const bool ) {}
void sx127xStartReceiving(void) {}
uint8_t sx127xISR(uint32_t *timestamp)
{
*timestamp = 0;
return 0;
}
void sx127xTransmitData(const uint8_t *, const uint8_t ) {}
void sx127xReceiveData(uint8_t *, const uint8_t ) {}
void sx127xSetFrequencyReg(const uint32_t ) {}
void sx127xGetLastPacketStats(int8_t *rssi, int8_t *snr)
{
*rssi = 0;
*snr = 0;
}
void sx127xAdjustFrequency(int32_t , const uint32_t ) {}
bool sx127xInit(IO_t , IO_t ) { return true; }
int scaleRange(int x, int srcFrom, int srcTo, int destFrom, int destTo) {
long int a = ((long int) destTo - (long int) destFrom) * ((long int) x - (long int) srcFrom);
long int b = (long int) srcTo - (long int) srcFrom;
return (a / b) + destFrom;
}
void expressLrsInitialiseTimer(TIM_TypeDef *, elrsReceiver_t *) {}
void expressLrsTimerEnableIRQs(void) {}
void expressLrsUpdateTimerInterval(uint16_t ) {}
void expressLrsUpdatePhaseShift(int32_t ) {}
void expressLrsTimerIncreaseFrequencyOffset(void) {}
void expressLrsTimerDecreaseFrequencyOffset(void) {}
void expressLrsTimerResetFrequencyOffset(void) {}
void expressLrsTimerStop(void) {}
void expressLrsTimerResume(void) {}
bool expressLrsTimerIsRunning(void) { return true; }
void expressLrsTimerDebug(void) {}
int32_t simpleLPFilterUpdate(simpleLowpassFilter_t *, int32_t ) { return 0; }
void simpleLPFilterInit(simpleLowpassFilter_t *, int32_t , int32_t ) {}
void dbgPinHi(int ) {}
void dbgPinLo(int ) {}
void initTelemetry(void) {}
bool getNextTelemetryPayload(uint8_t *, uint8_t **) { return false; }
void setTelemetryDataToTransmit(const uint8_t , uint8_t* , const uint8_t ) {}
bool isTelemetrySenderActive(void) { return false; }
void getCurrentTelemetryPayload(uint8_t *, uint8_t *, uint8_t **) {}
void confirmCurrentTelemetryPayload(const bool ) {}
void updateTelemetryRate(const uint16_t , const uint8_t , const uint8_t ) {}
}