mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 00:05:33 +03:00
Add FLRC F-modes to ELRS SPI implementation (#12936)
* Add FLRC F-modes to ELRS implementation * Code quality changes per review * Remove unused variable
This commit is contained in:
parent
75f94d8c5c
commit
1bcde73c3c
13 changed files with 361 additions and 188 deletions
|
@ -527,10 +527,6 @@ static const char* const lookupTableFreqDomain[] = {
|
||||||
"NONE",
|
"NONE",
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
static const char* const lookupTableSwitchMode[] = {
|
|
||||||
"WIDE", "HYBRID",
|
|
||||||
};
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define LOOKUP_TABLE_ENTRY(name) { name, ARRAYLEN(name) }
|
#define LOOKUP_TABLE_ENTRY(name) { name, ARRAYLEN(name) }
|
||||||
|
@ -657,7 +653,6 @@ const lookupTableEntry_t lookupTables[] = {
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_RX_EXPRESSLRS
|
#ifdef USE_RX_EXPRESSLRS
|
||||||
LOOKUP_TABLE_ENTRY(lookupTableFreqDomain),
|
LOOKUP_TABLE_ENTRY(lookupTableFreqDomain),
|
||||||
LOOKUP_TABLE_ENTRY(lookupTableSwitchMode),
|
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -1744,8 +1739,6 @@ const clivalue_t valueTable[] = {
|
||||||
#ifdef USE_RX_EXPRESSLRS
|
#ifdef USE_RX_EXPRESSLRS
|
||||||
{ "expresslrs_uid", VAR_UINT8 | MASTER_VALUE | MODE_ARRAY, .config.array.length = 6, PG_RX_EXPRESSLRS_SPI_CONFIG, offsetof(rxExpressLrsSpiConfig_t, UID) },
|
{ "expresslrs_uid", VAR_UINT8 | MASTER_VALUE | MODE_ARRAY, .config.array.length = 6, PG_RX_EXPRESSLRS_SPI_CONFIG, offsetof(rxExpressLrsSpiConfig_t, UID) },
|
||||||
{ "expresslrs_domain", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FREQ_DOMAIN }, PG_RX_EXPRESSLRS_SPI_CONFIG, offsetof(rxExpressLrsSpiConfig_t, domain) },
|
{ "expresslrs_domain", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FREQ_DOMAIN }, PG_RX_EXPRESSLRS_SPI_CONFIG, offsetof(rxExpressLrsSpiConfig_t, domain) },
|
||||||
{ "expresslrs_rate_index", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 3 }, PG_RX_EXPRESSLRS_SPI_CONFIG, offsetof(rxExpressLrsSpiConfig_t, rateIndex) },
|
|
||||||
{ "expresslrs_switch_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SWITCH_MODE }, PG_RX_EXPRESSLRS_SPI_CONFIG, offsetof(rxExpressLrsSpiConfig_t, switchMode) },
|
|
||||||
{ "expresslrs_model_id", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, UINT8_MAX }, PG_RX_EXPRESSLRS_SPI_CONFIG, offsetof(rxExpressLrsSpiConfig_t, modelId) },
|
{ "expresslrs_model_id", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, UINT8_MAX }, PG_RX_EXPRESSLRS_SPI_CONFIG, offsetof(rxExpressLrsSpiConfig_t, modelId) },
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -144,7 +144,6 @@ typedef enum {
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_RX_EXPRESSLRS
|
#ifdef USE_RX_EXPRESSLRS
|
||||||
TABLE_FREQ_DOMAIN,
|
TABLE_FREQ_DOMAIN,
|
||||||
TABLE_SWITCH_MODE,
|
|
||||||
#endif
|
#endif
|
||||||
LOOKUP_TABLE_COUNT
|
LOOKUP_TABLE_COUNT
|
||||||
} lookupTableIndex_e;
|
} lookupTableIndex_e;
|
||||||
|
|
|
@ -287,14 +287,17 @@ void sx127xStartReceiving(void)
|
||||||
sx127xSetMode(SX127x_OPMODE_RXCONTINUOUS);
|
sx127xSetMode(SX127x_OPMODE_RXCONTINUOUS);
|
||||||
}
|
}
|
||||||
|
|
||||||
void sx127xConfig(const sx127xBandwidth_e bw, const sx127xSpreadingFactor_e sf, const sx127xCodingRate_e cr,
|
void sx127xConfig(const uint8_t bw, const uint8_t sfbt, const uint8_t cr,
|
||||||
const uint32_t freq, const uint8_t preambleLen, const bool iqInverted)
|
const uint32_t freq, const uint8_t preambleLength, const bool iqInverted,
|
||||||
|
const uint32_t flrcSyncWord, const uint16_t flrcCrcSeed, const bool isFlrc)
|
||||||
{
|
{
|
||||||
|
UNUSED(flrcSyncWord); UNUSED(flrcCrcSeed); UNUSED(isFlrc);
|
||||||
|
|
||||||
sx127xConfigLoraDefaults(iqInverted);
|
sx127xConfigLoraDefaults(iqInverted);
|
||||||
sx127xSetPreambleLength(preambleLen);
|
sx127xSetPreambleLength(preambleLength);
|
||||||
sx127xSetOutputPower(SX127x_MAX_POWER);
|
sx127xSetOutputPower(SX127x_MAX_POWER);
|
||||||
sx127xSetSpreadingFactor(sf);
|
sx127xSetSpreadingFactor(sfbt);
|
||||||
sx127xSetBandwidthCodingRate(bw, cr, sf, false, false);
|
sx127xSetBandwidthCodingRate(bw, cr, sfbt, false, false);
|
||||||
sx127xSetFrequencyReg(freq);
|
sx127xSetFrequencyReg(freq);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -384,22 +387,22 @@ int32_t sx127xGetFrequencyError(const sx127xBandwidth_e bw)
|
||||||
return fErrorHZ;
|
return fErrorHZ;
|
||||||
}
|
}
|
||||||
|
|
||||||
void sx127xAdjustFrequency(int32_t offset, const uint32_t freq)
|
void sx127xAdjustFrequency(int32_t *offset, const uint32_t freq)
|
||||||
{
|
{
|
||||||
if (sx127xGetFrequencyErrorbool()) { //logic is flipped compared to original code
|
if (sx127xGetFrequencyErrorbool()) { //logic is flipped compared to original code
|
||||||
if (offset > SX127x_FREQ_CORRECTION_MIN) {
|
if (*offset > SX127x_FREQ_CORRECTION_MIN) {
|
||||||
offset -= 1;
|
*offset -= 1;
|
||||||
} else {
|
} else {
|
||||||
offset = 0; //reset because something went wrong
|
*offset = 0; //reset because something went wrong
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
if (offset < SX127x_FREQ_CORRECTION_MAX) {
|
if (*offset < SX127x_FREQ_CORRECTION_MAX) {
|
||||||
offset += 1;
|
*offset += 1;
|
||||||
} else {
|
} else {
|
||||||
offset = 0; //reset because something went wrong
|
*offset = 0; //reset because something went wrong
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
sx127xSetPPMoffsetReg(offset, freq); //as above but corrects a different PPM offset based on freq error
|
sx127xSetPPMoffsetReg(*offset, freq); //as above but corrects a different PPM offset based on freq error
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t sx127xUnsignedGetLastPacketRSSI(void)
|
uint8_t sx127xUnsignedGetLastPacketRSSI(void)
|
||||||
|
|
|
@ -319,13 +319,14 @@ void sx127xSetFrequencyReg(const uint32_t freq);
|
||||||
void sx127xTransmitData(const uint8_t *data, const uint8_t length);
|
void sx127xTransmitData(const uint8_t *data, const uint8_t length);
|
||||||
void sx127xReceiveData(uint8_t *data, const uint8_t length);
|
void sx127xReceiveData(uint8_t *data, const uint8_t length);
|
||||||
void sx127xStartReceiving(void);
|
void sx127xStartReceiving(void);
|
||||||
void sx127xConfig(const sx127xBandwidth_e bw, const sx127xSpreadingFactor_e sf, const sx127xCodingRate_e cr, const uint32_t freq, const uint8_t preambleLen, const bool iqInverted);
|
void sx127xConfig(const uint8_t bw, const uint8_t sfbt, const uint8_t cr,
|
||||||
|
const uint32_t freq, const uint8_t preambleLength, const bool iqInverted,
|
||||||
|
const uint32_t flrcSyncWord, const uint16_t flrcCrcSeed, const bool isFlrc);
|
||||||
uint32_t sx127xGetCurrBandwidth(const sx127xBandwidth_e bw);
|
uint32_t sx127xGetCurrBandwidth(const sx127xBandwidth_e bw);
|
||||||
uint32_t sx127xGetCurrBandwidthNormalisedShifted(const sx127xBandwidth_e bw);
|
uint32_t sx127xGetCurrBandwidthNormalisedShifted(const sx127xBandwidth_e bw);
|
||||||
void sx127xSetPPMoffsetReg(const int32_t offset, const uint32_t freq);
|
void sx127xSetPPMoffsetReg(const int32_t offset, const uint32_t freq);
|
||||||
int32_t sx127xGetFrequencyError(const sx127xBandwidth_e bw);
|
int32_t sx127xGetFrequencyError(const sx127xBandwidth_e bw);
|
||||||
void sx127xAdjustFrequency(int32_t offset, const uint32_t freq);
|
void sx127xAdjustFrequency(int32_t *offset, const uint32_t freq);
|
||||||
uint8_t sx127xUnsignedGetLastPacketRSSI(void);
|
uint8_t sx127xUnsignedGetLastPacketRSSI(void);
|
||||||
int8_t sx127xGetLastPacketRSSI(void);
|
int8_t sx127xGetLastPacketRSSI(void);
|
||||||
int8_t sx127xGetCurrRSSI(void);
|
int8_t sx127xGetCurrRSSI(void);
|
||||||
|
|
|
@ -52,9 +52,9 @@
|
||||||
|
|
||||||
// The following global variables are accessed from interrupt context to process the sequence of steps in packet processing
|
// The following global variables are accessed from interrupt context to process the sequence of steps in packet processing
|
||||||
// As there is only ever one device, no need to add a device context; globals will do
|
// As there is only ever one device, no need to add a device context; globals will do
|
||||||
static volatile dioReason_e irqReason; // Used to pass irq status from sx1280IrqStatusRead() to sx1280ProcessIrq()
|
static dioReasonFlags_e irqReason; // Used to pass irq status from sx1280IrqStatusRead() to sx1280ProcessIrq()
|
||||||
static volatile uint8_t packetStats[2];
|
static volatile uint8_t packetStats[2];
|
||||||
static volatile uint8_t FIFOaddr; // Used to pass data from sx1280GotFIFOAddr() to sx1280DoReadBuffer()
|
static uint8_t FIFOaddr; // Used to pass data from sx1280GotFIFOAddr() to sx1280DoReadBuffer()
|
||||||
|
|
||||||
static IO_t busy;
|
static IO_t busy;
|
||||||
|
|
||||||
|
@ -67,6 +67,7 @@ static busyIntContext_t busyIntContext;
|
||||||
static volatile timeUs_t sx1280Processing;
|
static volatile timeUs_t sx1280Processing;
|
||||||
|
|
||||||
static volatile bool pendingDoFHSS = false;
|
static volatile bool pendingDoFHSS = false;
|
||||||
|
static sx1280PacketTypes_e sx1280PacketMode;
|
||||||
|
|
||||||
#define SX1280_BUSY_TIMEOUT_US 1000
|
#define SX1280_BUSY_TIMEOUT_US 1000
|
||||||
|
|
||||||
|
@ -219,8 +220,7 @@ bool sx1280Init(IO_t resetPin, IO_t busyPin)
|
||||||
IOConfigGPIO(resetPin, IOCFG_IN_FLOATING); // leave floating, internal pullup on sx1280 side
|
IOConfigGPIO(resetPin, IOCFG_IN_FLOATING); // leave floating, internal pullup on sx1280 side
|
||||||
delay(20);
|
delay(20);
|
||||||
|
|
||||||
uint16_t firmwareRev = (((sx1280ReadRegister(REG_LR_FIRMWARE_VERSION_MSB)) << 8) | (sx1280ReadRegister(REG_LR_FIRMWARE_VERSION_MSB + 1)));
|
uint16_t firmwareRev = (((sx1280ReadRegister(SX1280_REG_FIRMWARE_VERSION_MSB)) << 8) | (sx1280ReadRegister(SX1280_REG_FIRMWARE_VERSION_MSB + 1)));
|
||||||
|
|
||||||
if ((firmwareRev == 0) || (firmwareRev == 65535)) {
|
if ((firmwareRev == 0) || (firmwareRev == 65535)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
@ -229,6 +229,10 @@ bool sx1280Init(IO_t resetPin, IO_t busyPin)
|
||||||
extDevice_t *dev = rxSpiGetDevice();
|
extDevice_t *dev = rxSpiGetDevice();
|
||||||
dev->callbackArg = (uint32_t)dev;
|
dev->callbackArg = (uint32_t)dev;
|
||||||
|
|
||||||
|
sx1280SetMode(SX1280_MODE_STDBY_RC);
|
||||||
|
sx1280WriteCommand(SX1280_RADIO_SET_AUTOFS, 0x01);
|
||||||
|
sx1280WriteRegister(SX1280_REG_RX_GAIN_REGIME, sx1280ReadRegister(SX1280_REG_RX_GAIN_REGIME) | 0xC0); //default is low power mode, switch to high sensitivity instead
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -338,31 +342,124 @@ uint8_t sx1280GetStatus(void)
|
||||||
return buffer[0];
|
return buffer[0];
|
||||||
}
|
}
|
||||||
|
|
||||||
void sx1280ConfigLoraDefaults(void)
|
static void sx1280ConfigModParamsLora(const sx1280LoraBandwidths_e bw, const sx1280LoraSpreadingFactors_e sf, const sx1280LoraCodingRates_e cr)
|
||||||
{
|
{
|
||||||
sx1280SetMode(SX1280_MODE_STDBY_RC); //step 1 put in STDBY_RC mode
|
uint8_t rfparams[3];
|
||||||
sx1280WriteCommand(SX1280_RADIO_SET_PACKETTYPE, SX1280_PACKET_TYPE_LORA); //Step 2: set packet type to LoRa
|
rfparams[0] = sf;
|
||||||
sx1280ConfigLoraModParams(SX1280_LORA_BW_0800, SX1280_LORA_SF6, SX1280_LORA_CR_4_7); //Step 5: Configure Modulation Params
|
rfparams[1] = bw;
|
||||||
sx1280WriteCommand(SX1280_RADIO_SET_AUTOFS, 0x01); //enable auto FS
|
rfparams[2] = cr;
|
||||||
sx1280WriteRegister(0x0891, (sx1280ReadRegister(0x0891) | 0xC0)); //default is low power mode, switch to high sensitivity instead
|
|
||||||
sx1280SetPacketParams(12, SX1280_LORA_PACKET_IMPLICIT, 8, SX1280_LORA_CRC_OFF, SX1280_LORA_IQ_NORMAL); //default params
|
sx1280WriteCommandBurst(SX1280_RADIO_SET_MODULATIONPARAMS, rfparams, 3);
|
||||||
sx1280SetFrequencyReg(fhssGetInitialFreq(0)); //Step 3: Set Freq
|
|
||||||
sx1280SetFifoAddr(0x00, 0x00); //Step 4: Config FIFO addr
|
switch (sf) {
|
||||||
sx1280SetDioIrqParams(SX1280_IRQ_RADIO_ALL, SX1280_IRQ_TX_DONE | SX1280_IRQ_RX_DONE, SX1280_IRQ_RADIO_NONE, SX1280_IRQ_RADIO_NONE); //set IRQ to both RXdone/TXdone on DIO1
|
case SX1280_LORA_SF5:
|
||||||
|
case SX1280_LORA_SF6:
|
||||||
|
sx1280WriteRegister(SX1280_REG_SF_ADDITIONAL_CONFIG, 0x1E); // SF5 or SF6
|
||||||
|
break;
|
||||||
|
case SX1280_LORA_SF7:
|
||||||
|
case SX1280_LORA_SF8:
|
||||||
|
sx1280WriteRegister(SX1280_REG_SF_ADDITIONAL_CONFIG, 0x37); // SF7 or SF8
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
sx1280WriteRegister(SX1280_REG_SF_ADDITIONAL_CONFIG, 0x32); // SF9, SF10, SF11, SF12
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void sx1280Config(const sx1280LoraBandwidths_e bw, const sx1280LoraSpreadingFactors_e sf, const sx1280LoraCodingRates_e cr,
|
static void sx1280SetPacketParamsLora(const uint8_t preambleLength, const sx1280LoraPacketLengthsModes_e headerType, const uint8_t payloadLength,
|
||||||
const uint32_t freq, const uint8_t preambleLength, const bool iqInverted)
|
const sx1280LoraCrcModes_e crc, const bool invertIQ)
|
||||||
{
|
{
|
||||||
sx1280SetMode(SX1280_MODE_SLEEP);
|
uint8_t buf[7];
|
||||||
sx1280PollBusy();
|
buf[0] = preambleLength;
|
||||||
|
buf[1] = headerType;
|
||||||
|
buf[2] = payloadLength;
|
||||||
|
buf[3] = crc;
|
||||||
|
buf[4] = invertIQ ? SX1280_LORA_IQ_INVERTED : SX1280_LORA_IQ_NORMAL;
|
||||||
|
buf[5] = 0x00;
|
||||||
|
buf[6] = 0x00;
|
||||||
|
|
||||||
sx1280ConfigLoraDefaults();
|
sx1280WriteCommandBurst(SX1280_RADIO_SET_PACKETPARAMS, buf, 7);
|
||||||
sx1280SetOutputPower(13); //default is max power (12.5dBm for SX1280 RX)
|
}
|
||||||
|
|
||||||
|
static void sx1280ConfigModParamsFlrc(const SX1280_RadioFlrcBandwidths_t bw, const SX1280_RadioFlrcCodingRates_t cr, const SX1280_RadioFlrcGaussianFilter_t bt)
|
||||||
|
{
|
||||||
|
uint8_t rfparams[3];
|
||||||
|
rfparams[0] = bw;
|
||||||
|
rfparams[1] = cr;
|
||||||
|
rfparams[2] = bt;
|
||||||
|
|
||||||
|
sx1280WriteCommandBurst(SX1280_RADIO_SET_MODULATIONPARAMS, rfparams, 3);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void sx1280SetPacketParamsFlrc(uint8_t PreambleLength, uint8_t HeaderType,
|
||||||
|
uint8_t PayloadLength, uint32_t syncWord, uint16_t crcSeed, uint8_t cr)
|
||||||
|
{
|
||||||
|
if (PreambleLength < 8)
|
||||||
|
PreambleLength = 8;
|
||||||
|
|
||||||
|
uint8_t buf[7];
|
||||||
|
buf[0] = ((PreambleLength / 4) - 1) << 4; // AGCPreambleLength
|
||||||
|
buf[1] = SX1280_FLRC_SYNC_WORD_LEN_P32S; // SyncWordLength
|
||||||
|
buf[2] = SX1280_FLRC_RX_MATCH_SYNC_WORD_1; // SyncWordMatch
|
||||||
|
buf[3] = HeaderType; // PacketType
|
||||||
|
buf[4] = PayloadLength; // PayloadLength
|
||||||
|
buf[5] = SX1280_FLRC_CRC_3_BYTE; // CrcLength
|
||||||
|
buf[6] = SX1280_FLRC_WHITENING_DISABLE; // Must be whitening disabled
|
||||||
|
sx1280WriteCommandBurst(SX1280_RADIO_SET_PACKETPARAMS, buf, 7);
|
||||||
|
|
||||||
|
// CRC seed (use dedicated cipher)
|
||||||
|
buf[0] = (uint8_t)(crcSeed >> 8);
|
||||||
|
buf[1] = (uint8_t)crcSeed;
|
||||||
|
sx1280WriteRegisterBurst(SX1280_REG_FLRC_CRC_SEED, buf, 2);
|
||||||
|
|
||||||
|
// Set SyncWord1
|
||||||
|
buf[0] = (uint8_t)(syncWord >> 24);
|
||||||
|
buf[1] = (uint8_t)(syncWord >> 16);
|
||||||
|
buf[2] = (uint8_t)(syncWord >> 8);
|
||||||
|
buf[3] = (uint8_t)syncWord;
|
||||||
|
|
||||||
|
// DS_SX1280-1_V3.2.pdf - 16.4 FLRC Modem: Increased PER in FLRC Packets with Synch Word
|
||||||
|
if (((cr == SX1280_FLRC_CR_1_2) || (cr == SX1280_FLRC_CR_3_4)) &&
|
||||||
|
((buf[0] == 0x8C && buf[1] == 0x38) || (buf[0] == 0x63 && buf[1] == 0x0E))) {
|
||||||
|
uint8_t temp = buf[0];
|
||||||
|
buf[0] = buf[1];
|
||||||
|
buf[1] = temp;
|
||||||
|
// For SX1280_FLRC_CR_3_4 the datasheet also says
|
||||||
|
// "In addition to this the two LSB values XX XX must not be in the range 0x0000 to 0x3EFF"
|
||||||
|
if (cr == SX1280_FLRC_CR_3_4 && buf[3] <= 0x3e)
|
||||||
|
buf[3] |= 0x80; // 0x80 or 0x40 would work
|
||||||
|
}
|
||||||
|
|
||||||
|
sx1280WriteRegisterBurst(SX1280_REG_FLRC_SYNC_WORD, buf, 4);
|
||||||
|
|
||||||
|
// Set permissible sync errors = 0
|
||||||
|
sx1280WriteRegister(SX1280_REG_FLRC_SYNC_ADDR_CTRL, sx1280ReadRegister(SX1280_REG_FLRC_SYNC_ADDR_CTRL) & 0xf0);
|
||||||
|
}
|
||||||
|
|
||||||
|
void sx1280Config(const uint8_t bw, const uint8_t sfbt, const uint8_t cr,
|
||||||
|
const uint32_t freq, const uint8_t preambleLength, const bool iqInverted,
|
||||||
|
const uint32_t flrcSyncWord, const uint16_t flrcCrcSeed, const bool isFlrc)
|
||||||
|
{
|
||||||
sx1280SetMode(SX1280_MODE_STDBY_RC);
|
sx1280SetMode(SX1280_MODE_STDBY_RC);
|
||||||
sx1280ClearIrqStatus(SX1280_IRQ_RADIO_ALL);
|
|
||||||
sx1280ConfigLoraModParams(bw, sf, cr);
|
sx1280PacketMode = (isFlrc) ? SX1280_PACKET_TYPE_FLRC : SX1280_PACKET_TYPE_LORA;
|
||||||
sx1280SetPacketParams(preambleLength, SX1280_LORA_PACKET_IMPLICIT, 8, SX1280_LORA_CRC_OFF, (sx1280LoraIqModes_e)((uint8_t)!iqInverted << 6)); // TODO don't make static etc.
|
sx1280WriteCommand(SX1280_RADIO_SET_PACKETTYPE, sx1280PacketMode);
|
||||||
|
|
||||||
|
if (isFlrc) {
|
||||||
|
sx1280ConfigModParamsFlrc(bw, cr, sfbt);
|
||||||
|
sx1280SetPacketParamsFlrc(preambleLength, SX1280_FLRC_PACKET_FIXED_LENGTH, 8, flrcSyncWord, flrcCrcSeed, cr);
|
||||||
|
} else {
|
||||||
|
sx1280ConfigModParamsLora(bw, sfbt, cr);
|
||||||
|
sx1280SetPacketParamsLora(preambleLength, SX1280_LORA_PACKET_FIXED_LENGTH, 8, SX1280_LORA_CRC_OFF, iqInverted);
|
||||||
|
}
|
||||||
|
|
||||||
|
sx1280SetDioIrqParams(
|
||||||
|
SX1280_IRQ_TX_DONE | SX1280_IRQ_RX_DONE | SX1280_IRQ_SYNCWORD_VALID | SX1280_IRQ_SYNCWORD_ERROR | SX1280_IRQ_CRC_ERROR, // irqMask
|
||||||
|
SX1280_IRQ_TX_DONE | SX1280_IRQ_RX_DONE, // dio1Mask
|
||||||
|
SX1280_IRQ_RADIO_NONE,
|
||||||
|
SX1280_IRQ_RADIO_NONE
|
||||||
|
);
|
||||||
|
|
||||||
|
sx1280SetOutputPower(13); //default is max power (12.5dBm for SX1280 RX)
|
||||||
sx1280SetFrequencyReg(freq);
|
sx1280SetFrequencyReg(freq);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -374,22 +471,6 @@ void sx1280SetOutputPower(const int8_t power)
|
||||||
sx1280WriteCommandBurst(SX1280_RADIO_SET_TXPARAMS, buf, 2);
|
sx1280WriteCommandBurst(SX1280_RADIO_SET_TXPARAMS, buf, 2);
|
||||||
}
|
}
|
||||||
|
|
||||||
void sx1280SetPacketParams(const uint8_t preambleLength, const sx1280LoraPacketLengthsModes_e headerType, const uint8_t payloadLength,
|
|
||||||
const sx1280LoraCrcModes_e crc, const sx1280LoraIqModes_e invertIQ)
|
|
||||||
{
|
|
||||||
uint8_t buf[7];
|
|
||||||
|
|
||||||
buf[0] = preambleLength;
|
|
||||||
buf[1] = headerType;
|
|
||||||
buf[2] = payloadLength;
|
|
||||||
buf[3] = crc;
|
|
||||||
buf[4] = invertIQ;
|
|
||||||
buf[5] = 0x00;
|
|
||||||
buf[6] = 0x00;
|
|
||||||
|
|
||||||
sx1280WriteCommandBurst(SX1280_RADIO_SET_PACKETPARAMS, buf, 7);
|
|
||||||
}
|
|
||||||
|
|
||||||
void sx1280SetMode(const sx1280OperatingModes_e opMode)
|
void sx1280SetMode(const sx1280OperatingModes_e opMode)
|
||||||
{
|
{
|
||||||
uint8_t buf[3];
|
uint8_t buf[3];
|
||||||
|
@ -428,33 +509,6 @@ void sx1280SetMode(const sx1280OperatingModes_e opMode)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void sx1280ConfigLoraModParams(const sx1280LoraBandwidths_e bw, const sx1280LoraSpreadingFactors_e sf, const sx1280LoraCodingRates_e cr)
|
|
||||||
{
|
|
||||||
// Care must therefore be taken to ensure that modulation parameters are set using the command
|
|
||||||
// SetModulationParam() only after defining the packet type SetPacketType() to be used
|
|
||||||
|
|
||||||
uint8_t rfparams[3] = {0};
|
|
||||||
|
|
||||||
rfparams[0] = (uint8_t)sf;
|
|
||||||
rfparams[1] = (uint8_t)bw;
|
|
||||||
rfparams[2] = (uint8_t)cr;
|
|
||||||
|
|
||||||
sx1280WriteCommandBurst(SX1280_RADIO_SET_MODULATIONPARAMS, rfparams, 3);
|
|
||||||
|
|
||||||
switch (sf) {
|
|
||||||
case SX1280_LORA_SF5:
|
|
||||||
case SX1280_LORA_SF6:
|
|
||||||
sx1280WriteRegister(0x925, 0x1E); // for SF5 or SF6
|
|
||||||
break;
|
|
||||||
case SX1280_LORA_SF7:
|
|
||||||
case SX1280_LORA_SF8:
|
|
||||||
sx1280WriteRegister(0x925, 0x37); // for SF7 or SF8
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
sx1280WriteRegister(0x925, 0x32); // for SF9, SF10, SF11, SF12
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void sx1280SetFrequencyReg(const uint32_t freqReg)
|
void sx1280SetFrequencyReg(const uint32_t freqReg)
|
||||||
{
|
{
|
||||||
uint8_t buf[3] = {0};
|
uint8_t buf[3] = {0};
|
||||||
|
@ -466,9 +520,8 @@ void sx1280SetFrequencyReg(const uint32_t freqReg)
|
||||||
sx1280WriteCommandBurst(SX1280_RADIO_SET_RFFREQUENCY, buf, 3);
|
sx1280WriteCommandBurst(SX1280_RADIO_SET_RFFREQUENCY, buf, 3);
|
||||||
}
|
}
|
||||||
|
|
||||||
void sx1280AdjustFrequency(int32_t offset, const uint32_t freq)
|
void sx1280AdjustFrequency(int32_t *offset, const uint32_t freq)
|
||||||
{
|
{
|
||||||
// just a stub to show that frequency adjustment is not used on this chip as opposed to sx127x
|
|
||||||
UNUSED(offset);
|
UNUSED(offset);
|
||||||
UNUSED(freq);
|
UNUSED(freq);
|
||||||
}
|
}
|
||||||
|
@ -527,10 +580,16 @@ void sx1280StartReceiving(void)
|
||||||
|
|
||||||
void sx1280GetLastPacketStats(int8_t *rssi, int8_t *snr)
|
void sx1280GetLastPacketStats(int8_t *rssi, int8_t *snr)
|
||||||
{
|
{
|
||||||
|
if (sx1280PacketMode == SX1280_PACKET_TYPE_FLRC) {
|
||||||
|
// No SNR in FLRC mode
|
||||||
|
*rssi = -(int8_t)(packetStats[1] / 2);
|
||||||
|
*snr = 0;
|
||||||
|
} else {
|
||||||
*rssi = -(int8_t)(packetStats[0] / 2);
|
*rssi = -(int8_t)(packetStats[0] / 2);
|
||||||
*snr = (int8_t) packetStats[1];
|
*snr = (int8_t)packetStats[1];
|
||||||
int8_t negOffset = (*snr < 0) ? (*snr / 4) : 0;
|
int8_t negOffset = (*snr < 0) ? (*snr / 4) : 0;
|
||||||
*rssi += negOffset;
|
*rssi += negOffset;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void sx1280DoFHSS(void)
|
void sx1280DoFHSS(void)
|
||||||
|
@ -600,7 +659,6 @@ FAST_IRQ_HANDLER static void sx1280IrqGetStatus(extiCallbackRec_t *cb)
|
||||||
}
|
}
|
||||||
|
|
||||||
// Read the IRQ status, and save it to irqStatus variable
|
// Read the IRQ status, and save it to irqStatus variable
|
||||||
|
|
||||||
FAST_IRQ_HANDLER static busStatus_e sx1280IrqStatusRead(uint32_t arg)
|
FAST_IRQ_HANDLER static busStatus_e sx1280IrqStatusRead(uint32_t arg)
|
||||||
{
|
{
|
||||||
extDevice_t *dev = (extDevice_t *)arg;
|
extDevice_t *dev = (extDevice_t *)arg;
|
||||||
|
@ -611,6 +669,14 @@ FAST_IRQ_HANDLER static busStatus_e sx1280IrqStatusRead(uint32_t arg)
|
||||||
irqReason = ELRS_DIO_TX_DONE;
|
irqReason = ELRS_DIO_TX_DONE;
|
||||||
} else if (irqStatus & SX1280_IRQ_RX_DONE) {
|
} else if (irqStatus & SX1280_IRQ_RX_DONE) {
|
||||||
irqReason = ELRS_DIO_RX_DONE;
|
irqReason = ELRS_DIO_RX_DONE;
|
||||||
|
|
||||||
|
if (sx1280PacketMode == SX1280_PACKET_TYPE_FLRC) {
|
||||||
|
// Reject the packet early if CRC/Syncword error or syncword valid not set
|
||||||
|
if ((irqStatus & (SX1280_IRQ_CRC_ERROR | SX1280_IRQ_SYNCWORD_ERROR)) ||
|
||||||
|
!(irqStatus & SX1280_IRQ_SYNCWORD_VALID)) {
|
||||||
|
irqReason |= ELRS_DIO_HWERROR;
|
||||||
|
}
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
irqReason = ELRS_DIO_UNKNOWN;
|
irqReason = ELRS_DIO_UNKNOWN;
|
||||||
}
|
}
|
||||||
|
@ -628,7 +694,6 @@ FAST_IRQ_HANDLER static void sx1280IrqClearStatus(extiCallbackRec_t *cb)
|
||||||
UNUSED(cb);
|
UNUSED(cb);
|
||||||
|
|
||||||
sx1280ClearBusyFn();
|
sx1280ClearBusyFn();
|
||||||
|
|
||||||
STATIC_DMA_DATA_AUTO uint8_t irqCmd[] = {SX1280_RADIO_CLR_IRQSTATUS, 0, 0};
|
STATIC_DMA_DATA_AUTO uint8_t irqCmd[] = {SX1280_RADIO_CLR_IRQSTATUS, 0, 0};
|
||||||
|
|
||||||
irqCmd[1] = (uint8_t)(((uint16_t)SX1280_IRQ_RADIO_ALL >> 8) & 0x00FF);
|
irqCmd[1] = (uint8_t)(((uint16_t)SX1280_IRQ_RADIO_ALL >> 8) & 0x00FF);
|
||||||
|
@ -647,7 +712,10 @@ FAST_IRQ_HANDLER static busStatus_e sx1280IrqCmdComplete(uint32_t arg)
|
||||||
{
|
{
|
||||||
UNUSED(arg);
|
UNUSED(arg);
|
||||||
|
|
||||||
|
// If HWERROR reported on RX, just do nothing and wait for the timer to expire
|
||||||
|
if (!(irqReason & ELRS_DIO_HWERROR)) {
|
||||||
sx1280SetBusyFn(sx1280ProcessIrq);
|
sx1280SetBusyFn(sx1280ProcessIrq);
|
||||||
|
}
|
||||||
|
|
||||||
return BUS_READY;
|
return BUS_READY;
|
||||||
}
|
}
|
||||||
|
@ -661,7 +729,7 @@ FAST_IRQ_HANDLER static void sx1280ProcessIrq(extiCallbackRec_t *cb)
|
||||||
|
|
||||||
sx1280ClearBusyFn();
|
sx1280ClearBusyFn();
|
||||||
|
|
||||||
if (irqReason == ELRS_DIO_RX_DONE || irqReason == ELRS_DIO_UNKNOWN) {
|
if (irqReason & ELRS_DIO_RX_DONE) {
|
||||||
// Fire off the chain to read and decode the packet from the radio
|
// Fire off the chain to read and decode the packet from the radio
|
||||||
// Get the buffer status to determine the FIFO address
|
// Get the buffer status to determine the FIFO address
|
||||||
STATIC_DMA_DATA_AUTO uint8_t cmdBufStatusCmd[] = {SX1280_RADIO_GET_RXBUFFERSTATUS, 0, 0, 0};
|
STATIC_DMA_DATA_AUTO uint8_t cmdBufStatusCmd[] = {SX1280_RADIO_GET_RXBUFFERSTATUS, 0, 0, 0};
|
||||||
|
|
|
@ -27,9 +27,14 @@
|
||||||
|
|
||||||
#include "common/time.h"
|
#include "common/time.h"
|
||||||
|
|
||||||
#define REG_LR_FIRMWARE_VERSION_MSB 0x0153 //The address of the register holding the firmware version MSB
|
#define SX1280_REG_FIRMWARE_VERSION_MSB 0x0153 //The address of the register holding the firmware version MSB
|
||||||
|
#define SX1280_REG_RX_GAIN_REGIME 0x0891
|
||||||
|
#define SX1280_REG_SF_ADDITIONAL_CONFIG 0x0925
|
||||||
#define SX1280_REG_LR_ESTIMATED_FREQUENCY_ERROR_MSB 0x0954
|
#define SX1280_REG_LR_ESTIMATED_FREQUENCY_ERROR_MSB 0x0954
|
||||||
#define SX1280_REG_LR_ESTIMATED_FREQUENCY_ERROR_MASK 0x0FFFFF
|
#define SX1280_REG_LR_ESTIMATED_FREQUENCY_ERROR_MASK 0x0FFFFF
|
||||||
|
#define SX1280_REG_FLRC_CRC_SEED 0x09C8
|
||||||
|
#define SX1280_REG_FLRC_SYNC_WORD 0x09CF
|
||||||
|
#define SX1280_REG_FLRC_SYNC_ADDR_CTRL 0x09CD
|
||||||
|
|
||||||
#define SX1280_XTAL_FREQ 52000000
|
#define SX1280_XTAL_FREQ 52000000
|
||||||
#define SX1280_FREQ_STEP (SX1280_XTAL_FREQ / 262144.0)
|
#define SX1280_FREQ_STEP (SX1280_XTAL_FREQ / 262144.0)
|
||||||
|
@ -175,6 +180,79 @@ typedef enum {
|
||||||
SX1280_LORA_CRC_OFF = 0x00, // CRC not used
|
SX1280_LORA_CRC_OFF = 0x00, // CRC not used
|
||||||
} sx1280LoraCrcModes_e;
|
} sx1280LoraCrcModes_e;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Represents the bandwidth values for FLRC packet type
|
||||||
|
*/
|
||||||
|
typedef enum {
|
||||||
|
SX1280_FLRC_BR_1_300_BW_1_2 = 0x45,
|
||||||
|
SX1280_FLRC_BR_1_000_BW_1_2 = 0x69,
|
||||||
|
SX1280_FLRC_BR_0_650_BW_0_6 = 0x86,
|
||||||
|
SX1280_FLRC_BR_0_520_BW_0_6 = 0xAA,
|
||||||
|
SX1280_FLRC_BR_0_325_BW_0_3 = 0xC7,
|
||||||
|
SX1280_FLRC_BR_0_260_BW_0_3 = 0xEB,
|
||||||
|
} SX1280_RadioFlrcBandwidths_t;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Represents the coding rate values for FLRC packet type
|
||||||
|
*/
|
||||||
|
typedef enum {
|
||||||
|
SX1280_FLRC_CR_1_2 = 0x00,
|
||||||
|
SX1280_FLRC_CR_3_4 = 0x02,
|
||||||
|
SX1280_FLRC_CR_1_0 = 0x04,
|
||||||
|
} SX1280_RadioFlrcCodingRates_t;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Represents the Gaussian filter value in FLRC packet types
|
||||||
|
*/
|
||||||
|
typedef enum {
|
||||||
|
SX1280_FLRC_BT_DIS = 0x00,
|
||||||
|
SX1280_FLRC_BT_1 = 0x10,
|
||||||
|
SX1280_FLRC_BT_0_5 = 0x20,
|
||||||
|
} SX1280_RadioFlrcGaussianFilter_t;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
SX1280_FLRC_SYNC_NOSYNC = 0x00,
|
||||||
|
SX1280_FLRC_SYNC_WORD_LEN_P32S = 0x04,
|
||||||
|
} SX1280_RadioFlrcSyncWordLen_t;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
SX1280_FLRC_RX_DISABLE_SYNC_WORD = 0x00,
|
||||||
|
SX1280_FLRC_RX_MATCH_SYNC_WORD_1 = 0x10,
|
||||||
|
SX1280_FLRC_RX_MATCH_SYNC_WORD_2 = 0x20,
|
||||||
|
SX1280_FLRC_RX_MATCH_SYNC_WORD_1_2 = 0x30,
|
||||||
|
SX1280_FLRC_RX_MATCH_SYNC_WORD_3 = 0x40,
|
||||||
|
SX1280_FLRC_RX_MATCH_SYNC_WORD_1_3 = 0x50,
|
||||||
|
SX1280_FLRC_RX_MATCH_SYNC_WORD_2_3 = 0x60,
|
||||||
|
SX1280_FLRC_RX_MATCH_SYNC_WORD_1_2_3 = 0x70,
|
||||||
|
} SX1280_RadioFlrcSyncWordCombination_t;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
SX1280_FLRC_PACKET_FIXED_LENGTH = 0x00,
|
||||||
|
SX1280_FLRC_PACKET_VARIABLE_LENGTH = 0x20,
|
||||||
|
} SX1280_RadioFlrcPacketType_t;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
SX1280_FLRC_CRC_OFF = 0x00,
|
||||||
|
SX1280_FLRC_CRC_2_BYTE = 0x10,
|
||||||
|
SX1280_FLRC_CRC_3_BYTE = 0x20,
|
||||||
|
SX1280_FLRC_CRC_4_BYTE = 0x30,
|
||||||
|
} SX1280_RadioFlrcCrc_t;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
SX1280_FLRC_WHITENING_DISABLE = 0x08,
|
||||||
|
} SX1280_RadioFlrcWhitening_t;
|
||||||
|
|
||||||
|
enum {
|
||||||
|
// Error Packet Status
|
||||||
|
SX1280_FLRC_PKT_ERROR_BUSY = 1 << 0,
|
||||||
|
SX1280_FLRC_PKT_ERROR_PKT_RCVD = 1 << 1,
|
||||||
|
SX1280_FLRC_PKT_ERROR_HDR_RCVD = 1 << 2,
|
||||||
|
SX1280_FLRC_PKT_ERROR_ABORT = 1 << 3,
|
||||||
|
SX1280_FLRC_PKT_ERROR_CRC = 1 << 4,
|
||||||
|
SX1280_FLRC_PKT_ERROR_LENGTH = 1 << 5,
|
||||||
|
SX1280_FLRC_PKT_ERROR_SYNC = 1 << 6,
|
||||||
|
};
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
SX1280_RADIO_GET_STATUS = 0xC0,
|
SX1280_RADIO_GET_STATUS = 0xC0,
|
||||||
SX1280_RADIO_WRITE_REGISTER = 0x18,
|
SX1280_RADIO_WRITE_REGISTER = 0x18,
|
||||||
|
@ -263,14 +341,13 @@ void sx1280WriteBuffer(const uint8_t offset, const uint8_t *buffer, const uint8_
|
||||||
void sx1280ReadBuffer(const uint8_t offset, uint8_t *buffer, const uint8_t size);
|
void sx1280ReadBuffer(const uint8_t offset, uint8_t *buffer, const uint8_t size);
|
||||||
|
|
||||||
uint8_t sx1280GetStatus(void);
|
uint8_t sx1280GetStatus(void);
|
||||||
void sx1280ConfigLoraDefaults(void);
|
void sx1280Config(const uint8_t bw, const uint8_t sfbt, const uint8_t cr,
|
||||||
void sx1280Config(const sx1280LoraBandwidths_e bw, const sx1280LoraSpreadingFactors_e sf, const sx1280LoraCodingRates_e cr, const uint32_t freq, const uint8_t preambleLength, const bool iqInverted);
|
const uint32_t freq, const uint8_t preambleLength, const bool iqInverted,
|
||||||
|
const uint32_t flrcSyncWord, const uint16_t flrcCrcSeed, const bool isFlrc);
|
||||||
void sx1280SetOutputPower(const int8_t power);
|
void sx1280SetOutputPower(const int8_t power);
|
||||||
void sx1280SetPacketParams(const uint8_t preambleLength, const sx1280LoraPacketLengthsModes_e headerType, const uint8_t payloadLength, const sx1280LoraCrcModes_e crc, const sx1280LoraIqModes_e invertIQ);
|
|
||||||
void sx1280SetMode(const sx1280OperatingModes_e opMode);
|
void sx1280SetMode(const sx1280OperatingModes_e opMode);
|
||||||
void sx1280ConfigLoraModParams(const sx1280LoraBandwidths_e bw, const sx1280LoraSpreadingFactors_e sf, const sx1280LoraCodingRates_e cr);
|
|
||||||
void sx1280SetFrequencyReg(const uint32_t freqReg);
|
void sx1280SetFrequencyReg(const uint32_t freqReg);
|
||||||
void sx1280AdjustFrequency(int32_t offset, const uint32_t freq);
|
void sx1280AdjustFrequency(int32_t *offset, const uint32_t freq);
|
||||||
void sx1280SetFifoAddr(const uint8_t txBaseAddr, const uint8_t rxBaseAddr);
|
void sx1280SetFifoAddr(const uint8_t txBaseAddr, const uint8_t rxBaseAddr);
|
||||||
void sx1280SetDioIrqParams(const uint16_t irqMask, const uint16_t dio1Mask, const uint16_t dio2Mask, const uint16_t dio3Mask);
|
void sx1280SetDioIrqParams(const uint16_t irqMask, const uint16_t dio1Mask, const uint16_t dio2Mask, const uint16_t dio3Mask);
|
||||||
void sx1280ClearIrqStatus(const uint16_t irqMask);
|
void sx1280ClearIrqStatus(const uint16_t irqMask);
|
||||||
|
|
|
@ -43,7 +43,6 @@ PG_RESET_TEMPLATE(rxExpressLrsSpiConfig_t, rxExpressLrsSpiConfig,
|
||||||
.resetIoTag = IO_TAG(RX_EXPRESSLRS_SPI_RESET_PIN),
|
.resetIoTag = IO_TAG(RX_EXPRESSLRS_SPI_RESET_PIN),
|
||||||
.busyIoTag = IO_TAG(RX_EXPRESSLRS_SPI_BUSY_PIN),
|
.busyIoTag = IO_TAG(RX_EXPRESSLRS_SPI_BUSY_PIN),
|
||||||
.UID = {0, 0, 0, 0, 0, 0},
|
.UID = {0, 0, 0, 0, 0, 0},
|
||||||
.switchMode = 0,
|
|
||||||
.domain = 0,
|
.domain = 0,
|
||||||
.rateIndex = 0,
|
.rateIndex = 0,
|
||||||
.modelId = 0xFF,
|
.modelId = 0xFF,
|
||||||
|
|
|
@ -28,7 +28,6 @@ typedef struct rxExpressLrsSpiConfig_s {
|
||||||
ioTag_t resetIoTag;
|
ioTag_t resetIoTag;
|
||||||
ioTag_t busyIoTag;
|
ioTag_t busyIoTag;
|
||||||
uint8_t UID[6];
|
uint8_t UID[6];
|
||||||
uint8_t switchMode;
|
|
||||||
uint8_t domain;
|
uint8_t domain;
|
||||||
uint8_t rateIndex;
|
uint8_t rateIndex;
|
||||||
uint8_t modelId;
|
uint8_t modelId;
|
||||||
|
|
|
@ -281,7 +281,7 @@ static void unpackChannelDataHybridWide(uint16_t *rcData, volatile elrsOtaPacket
|
||||||
} else {
|
} else {
|
||||||
uint8_t bins;
|
uint8_t bins;
|
||||||
uint16_t switchValue;
|
uint16_t switchValue;
|
||||||
if (currTlmDenom < 8) {
|
if (currTlmDenom > 1 && currTlmDenom < 8) {
|
||||||
bins = 63;
|
bins = 63;
|
||||||
switchValue = switchByte & 0x3F; // 6-bit
|
switchValue = switchByte & 0x3F; // 6-bit
|
||||||
} else {
|
} else {
|
||||||
|
@ -332,10 +332,21 @@ static void setRfLinkRate(const uint8_t index)
|
||||||
receiver.rfPerfParams = &rfPerfConfig[0][index];
|
receiver.rfPerfParams = &rfPerfConfig[0][index];
|
||||||
#endif
|
#endif
|
||||||
receiver.currentFreq = fhssGetInitialFreq(receiver.freqOffset);
|
receiver.currentFreq = fhssGetInitialFreq(receiver.freqOffset);
|
||||||
|
|
||||||
// Wait for (11/10) 110% of time it takes to cycle through all freqs in FHSS table (in ms)
|
// Wait for (11/10) 110% of time it takes to cycle through all freqs in FHSS table (in ms)
|
||||||
receiver.cycleIntervalMs = ((uint32_t)11U * fhssGetNumEntries() * receiver.modParams->fhssHopInterval * receiver.modParams->interval) / (10U * 1000U);
|
receiver.cycleIntervalMs = ((uint32_t)11U * fhssGetNumEntries() * receiver.modParams->fhssHopInterval * receiver.modParams->interval) / (10U * 1000U);
|
||||||
|
|
||||||
receiver.config(receiver.modParams->bw, receiver.modParams->sf, receiver.modParams->cr, receiver.currentFreq, receiver.modParams->preambleLen, receiver.UID[5] & 0x01);
|
receiver.config(
|
||||||
|
receiver.modParams->bw,
|
||||||
|
receiver.modParams->sf,
|
||||||
|
receiver.modParams->cr,
|
||||||
|
receiver.currentFreq,
|
||||||
|
receiver.modParams->preambleLen,
|
||||||
|
receiver.UID[5] & 0x01,
|
||||||
|
elrsUidToSeed(receiver.UID),
|
||||||
|
crcInitializer,
|
||||||
|
receiver.modParams->radioType == RADIO_TYPE_SX128x_FLRC
|
||||||
|
);
|
||||||
#if defined(USE_RX_SX1280)
|
#if defined(USE_RX_SX1280)
|
||||||
if (rxExpressLrsSpiConfig()->domain == CE2400)
|
if (rxExpressLrsSpiConfig()->domain == CE2400)
|
||||||
sx1280SetOutputPower(10);
|
sx1280SetOutputPower(10);
|
||||||
|
@ -566,8 +577,8 @@ static void gotConnection(const uint32_t timeStampMs)
|
||||||
receiver.timerState = ELRS_TIM_TENTATIVE;
|
receiver.timerState = ELRS_TIM_TENTATIVE;
|
||||||
receiver.gotConnectionMs = timeStampMs;
|
receiver.gotConnectionMs = timeStampMs;
|
||||||
|
|
||||||
if (rxExpressLrsSpiConfig()->rateIndex != receiver.rateIndex) {
|
if (rxExpressLrsSpiConfig()->rateIndex != receiver.nextRateIndex) {
|
||||||
rxExpressLrsSpiConfigMutable()->rateIndex = receiver.rateIndex;
|
rxExpressLrsSpiConfigMutable()->rateIndex = receiver.nextRateIndex;
|
||||||
receiver.configChanged = true;
|
receiver.configChanged = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -575,7 +586,7 @@ static void gotConnection(const uint32_t timeStampMs)
|
||||||
//setup radio
|
//setup radio
|
||||||
static void initializeReceiver(void)
|
static void initializeReceiver(void)
|
||||||
{
|
{
|
||||||
fhssGenSequence(receiver.UID, rxExpressLrsSpiConfig()->domain);
|
fhssGenSequence(elrsUidToSeed(receiver.UID), rxExpressLrsSpiConfig()->domain);
|
||||||
lqReset();
|
lqReset();
|
||||||
receiver.nonceRX = 0;
|
receiver.nonceRX = 0;
|
||||||
receiver.freqOffset = 0;
|
receiver.freqOffset = 0;
|
||||||
|
@ -587,6 +598,7 @@ static void initializeReceiver(void)
|
||||||
#endif //USE_RX_RSNR
|
#endif //USE_RX_RSNR
|
||||||
receiver.snr = 0;
|
receiver.snr = 0;
|
||||||
receiver.uplinkLQ = 0;
|
receiver.uplinkLQ = 0;
|
||||||
|
receiver.switchMode = 0;
|
||||||
receiver.rateIndex = receiver.inBindingMode ? bindingRateIndex : rxExpressLrsSpiConfig()->rateIndex;
|
receiver.rateIndex = receiver.inBindingMode ? bindingRateIndex : rxExpressLrsSpiConfig()->rateIndex;
|
||||||
setRfLinkRate(receiver.rateIndex);
|
setRfLinkRate(receiver.rateIndex);
|
||||||
|
|
||||||
|
@ -606,7 +618,7 @@ static void initializeReceiver(void)
|
||||||
receiver.lastSyncPacketMs = timeStampMs;
|
receiver.lastSyncPacketMs = timeStampMs;
|
||||||
receiver.lastValidPacketMs = timeStampMs;
|
receiver.lastValidPacketMs = timeStampMs;
|
||||||
|
|
||||||
receiver.rfModeCycleMultiplier = 1;
|
receiver.rfModeCycleMultiplier = ELRS_MODE_CYCLE_MULTIPLIER_SLOW / 2;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void unpackBindPacket(volatile uint8_t *packet)
|
static void unpackBindPacket(volatile uint8_t *packet)
|
||||||
|
@ -681,13 +693,8 @@ static bool processRFSyncPacket(volatile elrsOtaPacket_t const * const otaPktPtr
|
||||||
|
|
||||||
// Will change the packet air rate in loop() if this changes
|
// Will change the packet air rate in loop() if this changes
|
||||||
receiver.nextRateIndex = domainIsTeam24() ? airRateIndexToIndex24(otaPktPtr->sync.rateIndex, receiver.rateIndex) : airRateIndexToIndex900(otaPktPtr->sync.rateIndex, receiver.rateIndex);
|
receiver.nextRateIndex = domainIsTeam24() ? airRateIndexToIndex24(otaPktPtr->sync.rateIndex, receiver.rateIndex) : airRateIndexToIndex900(otaPktPtr->sync.rateIndex, receiver.rateIndex);
|
||||||
uint8_t switchEncMode = otaPktPtr->sync.switchEncMode;
|
|
||||||
|
|
||||||
// Update switch mode encoding immediately
|
// Update switch mode encoding immediately
|
||||||
if (switchEncMode != rxExpressLrsSpiConfig()->switchMode) {
|
receiver.switchMode = otaPktPtr->sync.switchEncMode;
|
||||||
rxExpressLrsSpiConfigMutable()->switchMode = switchEncMode;
|
|
||||||
receiver.configChanged = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Update TLM ratio
|
// Update TLM ratio
|
||||||
uint8_t tlmRateIn = otaPktPtr->sync.newTlmRatio + TLM_RATIO_NO_TLM;
|
uint8_t tlmRateIn = otaPktPtr->sync.newTlmRatio + TLM_RATIO_NO_TLM;
|
||||||
|
@ -721,7 +728,7 @@ static bool validatePacketCrcStd(volatile elrsOtaPacket_t * const otaPktPtr)
|
||||||
uint16_t const inCRC = ((uint16_t) otaPktPtr->crcHigh << 8) + otaPktPtr->crcLow;
|
uint16_t const inCRC = ((uint16_t) otaPktPtr->crcHigh << 8) + otaPktPtr->crcLow;
|
||||||
// For smHybrid the CRC only has the packet type in byte 0
|
// For smHybrid the CRC only has the packet type in byte 0
|
||||||
// For smWide the FHSS slot is added to the CRC in byte 0 on PACKET_TYPE_RCDATAs
|
// For smWide the FHSS slot is added to the CRC in byte 0 on PACKET_TYPE_RCDATAs
|
||||||
if (otaPktPtr->type == ELRS_RC_DATA_PACKET && rxExpressLrsSpiConfig()->switchMode == SM_WIDE) {
|
if (otaPktPtr->type == ELRS_RC_DATA_PACKET && receiver.switchMode == SM_WIDE) {
|
||||||
otaPktPtr->crcHigh = (receiver.nonceRX % receiver.modParams->fhssHopInterval) + 1;
|
otaPktPtr->crcHigh = (receiver.nonceRX % receiver.modParams->fhssHopInterval) + 1;
|
||||||
} else {
|
} else {
|
||||||
otaPktPtr->crcHigh = 0;
|
otaPktPtr->crcHigh = 0;
|
||||||
|
@ -750,7 +757,7 @@ rx_spi_received_e processRFPacket(volatile uint8_t *payload, uint32_t timeStampU
|
||||||
// Must be fully connected to process RC packets, prevents processing RC
|
// Must be fully connected to process RC packets, prevents processing RC
|
||||||
// during sync, where packets can be received before connection
|
// during sync, where packets can be received before connection
|
||||||
if (receiver.connectionState == ELRS_CONNECTED && connectionHasModelMatch) {
|
if (receiver.connectionState == ELRS_CONNECTED && connectionHasModelMatch) {
|
||||||
if (rxExpressLrsSpiConfig()->switchMode == SM_WIDE) {
|
if (receiver.switchMode == SM_WIDE) {
|
||||||
wideSwitchIndex = hybridWideNonceToSwitchIndex(receiver.nonceRX);
|
wideSwitchIndex = hybridWideNonceToSwitchIndex(receiver.nonceRX);
|
||||||
if ((currTlmDenom < 8) || wideSwitchIndex == 7) {
|
if ((currTlmDenom < 8) || wideSwitchIndex == 7) {
|
||||||
confirmCurrentTelemetryPayload((otaPktPtr->rc.switches & 0x40) >> 6);
|
confirmCurrentTelemetryPayload((otaPktPtr->rc.switches & 0x40) >> 6);
|
||||||
|
@ -776,6 +783,8 @@ rx_spi_received_e processRFPacket(volatile uint8_t *payload, uint32_t timeStampU
|
||||||
|
|
||||||
// Store the LQ/RSSI/Antenna
|
// Store the LQ/RSSI/Antenna
|
||||||
receiver.getRfLinkInfo(&receiver.rssi, &receiver.snr);
|
receiver.getRfLinkInfo(&receiver.rssi, &receiver.snr);
|
||||||
|
receiver.handleFreqCorrection(&receiver.freqOffset, receiver.currentFreq);
|
||||||
|
|
||||||
meanAccumulatorAdd(&snrFilter, receiver.snr);
|
meanAccumulatorAdd(&snrFilter, receiver.snr);
|
||||||
// Received a packet, that's the definition of LQ
|
// Received a packet, that's the definition of LQ
|
||||||
lqIncrease();
|
lqIncrease();
|
||||||
|
@ -1078,7 +1087,7 @@ void expressLrsSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
|
||||||
{
|
{
|
||||||
if (rcData && payload) {
|
if (rcData && payload) {
|
||||||
volatile elrsOtaPacket_t * const otaPktPtr = (elrsOtaPacket_t * const) payload;
|
volatile elrsOtaPacket_t * const otaPktPtr = (elrsOtaPacket_t * const) payload;
|
||||||
rxExpressLrsSpiConfig()->switchMode == SM_WIDE ? unpackChannelDataHybridWide(rcData, otaPktPtr) : unpackChannelDataHybridSwitch8(rcData, otaPktPtr);
|
receiver.switchMode == SM_WIDE ? unpackChannelDataHybridWide(rcData, otaPktPtr) : unpackChannelDataHybridSwitch8(rcData, otaPktPtr);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1098,10 +1107,10 @@ void expressLrsDoTelem(void)
|
||||||
expressLrsHandleTelemetryUpdate();
|
expressLrsHandleTelemetryUpdate();
|
||||||
expressLrsSendTelemResp();
|
expressLrsSendTelemResp();
|
||||||
|
|
||||||
if (!domainIsTeam24() && !receiver.didFhss && !expressLrsTelemRespReq() && lqPeriodIsSet()) {
|
if (!expressLrsTelemRespReq() && lqPeriodIsSet()) {
|
||||||
// TODO No need to handle this on SX1280, but will on SX127x
|
// TODO No need to handle this on SX1280, but will on SX127x
|
||||||
// TODO this needs to be DMA aswell, SX127x unlikely to work right now
|
// TODO this needs to be DMA aswell, SX127x unlikely to work right now
|
||||||
receiver.handleFreqCorrection(receiver.freqOffset, receiver.currentFreq); //corrects for RX freq offset
|
receiver.handleFreqCorrection(&receiver.freqOffset, receiver.currentFreq); //corrects for RX freq offset
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -53,18 +53,20 @@ static uint32_t freqSpread = 0;
|
||||||
elrsModSettings_t airRateConfig[][ELRS_RATE_MAX] = {
|
elrsModSettings_t airRateConfig[][ELRS_RATE_MAX] = {
|
||||||
#ifdef USE_RX_SX127X
|
#ifdef USE_RX_SX127X
|
||||||
{
|
{
|
||||||
{0, RATE_LORA_200HZ, SX127x_BW_500_00_KHZ, SX127x_SF_6, SX127x_CR_4_7, 5000, TLM_RATIO_1_64, 4, 8},
|
{0, RADIO_TYPE_SX127x_LORA, RATE_LORA_200HZ, SX127x_BW_500_00_KHZ, SX127x_SF_6, SX127x_CR_4_7, 5000, TLM_RATIO_1_64, 4, 8},
|
||||||
{1, RATE_LORA_100HZ, SX127x_BW_500_00_KHZ, SX127x_SF_7, SX127x_CR_4_7, 10000, TLM_RATIO_1_64, 4, 8},
|
{1, RADIO_TYPE_SX127x_LORA, RATE_LORA_100HZ, SX127x_BW_500_00_KHZ, SX127x_SF_7, SX127x_CR_4_7, 10000, TLM_RATIO_1_64, 4, 8},
|
||||||
{2, RATE_LORA_50HZ, SX127x_BW_500_00_KHZ, SX127x_SF_8, SX127x_CR_4_7, 20000, TLM_RATIO_1_16, 4, 10},
|
{2, RADIO_TYPE_SX127x_LORA, RATE_LORA_50HZ, SX127x_BW_500_00_KHZ, SX127x_SF_8, SX127x_CR_4_7, 20000, TLM_RATIO_1_16, 4, 10},
|
||||||
{3, RATE_LORA_25HZ, SX127x_BW_500_00_KHZ, SX127x_SF_9, SX127x_CR_4_7, 40000, TLM_RATIO_1_8, 2, 10}
|
{3, RADIO_TYPE_SX127x_LORA, RATE_LORA_25HZ, SX127x_BW_500_00_KHZ, SX127x_SF_9, SX127x_CR_4_7, 40000, TLM_RATIO_1_8, 2, 10},
|
||||||
},
|
},
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_RX_SX1280
|
#ifdef USE_RX_SX1280
|
||||||
{
|
{
|
||||||
{0, RATE_LORA_500HZ, SX1280_LORA_BW_0800, SX1280_LORA_SF5, SX1280_LORA_CR_LI_4_6, 2000, TLM_RATIO_1_128, 4, 12},
|
{0, RADIO_TYPE_SX128x_FLRC, RATE_FLRC_1000HZ, SX1280_FLRC_BR_0_650_BW_0_6, SX1280_FLRC_BT_1, SX1280_FLRC_CR_1_2, 1000, TLM_RATIO_1_128, 2, 32},
|
||||||
{1, RATE_LORA_250HZ, SX1280_LORA_BW_0800, SX1280_LORA_SF6, SX1280_LORA_CR_LI_4_7, 4000, TLM_RATIO_1_64, 4, 14},
|
{1, RADIO_TYPE_SX128x_FLRC, RATE_FLRC_500HZ, SX1280_FLRC_BR_0_650_BW_0_6, SX1280_FLRC_BT_1, SX1280_FLRC_CR_1_2, 2000, TLM_RATIO_1_128, 2, 32},
|
||||||
{2, RATE_LORA_150HZ, SX1280_LORA_BW_0800, SX1280_LORA_SF7, SX1280_LORA_CR_LI_4_7, 6666, TLM_RATIO_1_32, 4, 12},
|
{2, RADIO_TYPE_SX128x_LORA, RATE_LORA_500HZ, SX1280_LORA_BW_0800, SX1280_LORA_SF5, SX1280_LORA_CR_LI_4_6, 2000, TLM_RATIO_1_128, 4, 12},
|
||||||
{3, RATE_LORA_50HZ, SX1280_LORA_BW_0800, SX1280_LORA_SF8, SX1280_LORA_CR_LI_4_7, 20000, TLM_RATIO_1_16, 2, 12}
|
{3, RADIO_TYPE_SX128x_LORA, RATE_LORA_250HZ, SX1280_LORA_BW_0800, SX1280_LORA_SF6, SX1280_LORA_CR_LI_4_7, 4000, TLM_RATIO_1_64, 4, 14},
|
||||||
|
{4, RADIO_TYPE_SX128x_LORA, RATE_LORA_150HZ, SX1280_LORA_BW_0800, SX1280_LORA_SF7, SX1280_LORA_CR_LI_4_7, 6666, TLM_RATIO_1_32, 4, 12},
|
||||||
|
{5, RADIO_TYPE_SX128x_LORA, RATE_LORA_50HZ, SX1280_LORA_BW_0800, SX1280_LORA_SF8, SX1280_LORA_CR_LI_4_7, 20000, TLM_RATIO_1_16, 2, 12},
|
||||||
},
|
},
|
||||||
#endif
|
#endif
|
||||||
#if !defined(USE_RX_SX127X) && !defined(USE_RX_SX1280)
|
#if !defined(USE_RX_SX127X) && !defined(USE_RX_SX1280)
|
||||||
|
@ -78,15 +80,17 @@ elrsRfPerfParams_t rfPerfConfig[][ELRS_RATE_MAX] = {
|
||||||
{0, RATE_LORA_200HZ, -112, 4380, 3000, 2500, 600, 5000},
|
{0, RATE_LORA_200HZ, -112, 4380, 3000, 2500, 600, 5000},
|
||||||
{1, RATE_LORA_100HZ, -117, 8770, 3500, 2500, 600, 5000},
|
{1, RATE_LORA_100HZ, -117, 8770, 3500, 2500, 600, 5000},
|
||||||
{2, RATE_LORA_50HZ, -120, 17540, 4000, 2500, 600, 5000},
|
{2, RATE_LORA_50HZ, -120, 17540, 4000, 2500, 600, 5000},
|
||||||
{3, RATE_LORA_25HZ, -123, 17540, 6000, 4000, 0, 5000}
|
{3, RATE_LORA_25HZ, -123, 17540, 6000, 4000, 0, 5000},
|
||||||
},
|
},
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_RX_SX1280
|
#ifdef USE_RX_SX1280
|
||||||
{
|
{
|
||||||
{0, RATE_LORA_500HZ, -105, 1665, 2500, 2500, 3, 5000},
|
{0, RATE_FLRC_1000HZ, -104, 389, 2500, 2500, 0, 5000},
|
||||||
{1, RATE_LORA_250HZ, -108, 3300, 3000, 2500, 6, 5000},
|
{1, RATE_FLRC_500HZ, -104, 389, 2500, 2500, 0, 5000},
|
||||||
{2, RATE_LORA_150HZ, -112, 5871, 3500, 2500, 10, 5000},
|
{2, RATE_LORA_500HZ, -105, 1665, 2500, 2500, 3, 5000},
|
||||||
{3, RATE_LORA_50HZ, -115, 10798, 4000, 2500, 0, 5000}
|
{3, RATE_LORA_250HZ, -108, 3300, 3000, 2500, 6, 5000},
|
||||||
|
{4, RATE_LORA_150HZ, -112, 5871, 3500, 2500, 10, 5000},
|
||||||
|
{5, RATE_LORA_50HZ, -115, 10798, 4000, 2500, 0, 5000},
|
||||||
},
|
},
|
||||||
#endif
|
#endif
|
||||||
#if !defined(USE_RX_SX127X) && !defined(USE_RX_SX1280)
|
#if !defined(USE_RX_SX127X) && !defined(USE_RX_SX1280)
|
||||||
|
@ -186,9 +190,9 @@ Approach:
|
||||||
another random entry, excluding the sync channel.
|
another random entry, excluding the sync channel.
|
||||||
|
|
||||||
*/
|
*/
|
||||||
void fhssGenSequence(const uint8_t UID[], const elrsFreqDomain_e dom)
|
void fhssGenSequence(const uint32_t uidSeed, const elrsFreqDomain_e dom)
|
||||||
{
|
{
|
||||||
seed = (((long)UID[2] << 24) + ((long)UID[3] << 16) + ((long)UID[4] << 8) + UID[5]) ^ ELRS_OTA_VERSION_ID;
|
seed = uidSeed;
|
||||||
fhssConfig = &fhssConfigs[dom];
|
fhssConfig = &fhssConfigs[dom];
|
||||||
seqCount = (256 / MAX(fhssConfig->freqCount, 1)) * fhssConfig->freqCount;
|
seqCount = (256 / MAX(fhssConfig->freqCount, 1)) * fhssConfig->freqCount;
|
||||||
syncChannel = (fhssConfig->freqCount / 2) + 1;
|
syncChannel = (fhssConfig->freqCount / 2) + 1;
|
||||||
|
@ -234,6 +238,8 @@ uint8_t tlmRatioEnumToValue(const elrsTlmRatio_e enumval)
|
||||||
uint16_t rateEnumToHz(const elrsRfRate_e eRate)
|
uint16_t rateEnumToHz(const elrsRfRate_e eRate)
|
||||||
{
|
{
|
||||||
switch (eRate) {
|
switch (eRate) {
|
||||||
|
case RATE_FLRC_1000HZ: return 1000;
|
||||||
|
case RATE_FLRC_500HZ: return 500;
|
||||||
case RATE_LORA_500HZ: return 500;
|
case RATE_LORA_500HZ: return 500;
|
||||||
case RATE_LORA_250HZ: return 250;
|
case RATE_LORA_250HZ: return 250;
|
||||||
case RATE_LORA_200HZ: return 200;
|
case RATE_LORA_200HZ: return 200;
|
||||||
|
@ -262,6 +268,12 @@ uint16_t txPowerIndexToValue(const uint8_t index)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
uint32_t elrsUidToSeed(const uint8_t UID[])
|
||||||
|
{
|
||||||
|
return ((uint32_t)UID[2] << 24) + ((uint32_t)UID[3] << 16) +
|
||||||
|
((uint32_t)UID[4] << 8) + (UID[5] ^ ELRS_OTA_VERSION_ID);
|
||||||
|
}
|
||||||
|
|
||||||
#define ELRS_LQ_DEPTH 4 //100 % 32
|
#define ELRS_LQ_DEPTH 4 //100 % 32
|
||||||
|
|
||||||
typedef struct linkQuality_s {
|
typedef struct linkQuality_s {
|
||||||
|
@ -374,26 +386,26 @@ uint8_t airRateIndexToIndex900(uint8_t airRate, uint8_t currentIndex)
|
||||||
uint8_t airRateIndexToIndex24(uint8_t airRate, uint8_t currentIndex)
|
uint8_t airRateIndexToIndex24(uint8_t airRate, uint8_t currentIndex)
|
||||||
{
|
{
|
||||||
switch (airRate) {
|
switch (airRate) {
|
||||||
case 0:
|
case 0: // F1000
|
||||||
return currentIndex;
|
|
||||||
case 1:
|
|
||||||
return currentIndex;
|
|
||||||
case 2:
|
|
||||||
return currentIndex;
|
|
||||||
case 3:
|
|
||||||
return currentIndex;
|
|
||||||
case 4:
|
|
||||||
return 0;
|
return 0;
|
||||||
case 5:
|
case 1: // F500
|
||||||
return currentIndex;
|
|
||||||
case 6:
|
|
||||||
return 1;
|
return 1;
|
||||||
case 7:
|
case 2: // D500
|
||||||
return 2;
|
|
||||||
case 8:
|
|
||||||
return currentIndex;
|
return currentIndex;
|
||||||
case 9:
|
case 3: // D250
|
||||||
|
return currentIndex;
|
||||||
|
case 4: // 500Hz
|
||||||
|
return 2;
|
||||||
|
case 5: // 333Hz Full
|
||||||
|
return currentIndex;
|
||||||
|
case 6: // 250Hz
|
||||||
return 3;
|
return 3;
|
||||||
|
case 7: // 150Hz
|
||||||
|
return 4;
|
||||||
|
case 8: // 100Hz Full
|
||||||
|
return currentIndex;
|
||||||
|
case 9: // 50Hz
|
||||||
|
return 5;
|
||||||
default:
|
default:
|
||||||
return currentIndex;
|
return currentIndex;
|
||||||
}
|
}
|
||||||
|
|
|
@ -54,8 +54,10 @@
|
||||||
#define FREQ_HZ_TO_REG_VAL_900(freq) ((uint32_t)(freq / SX127x_FREQ_STEP))
|
#define FREQ_HZ_TO_REG_VAL_900(freq) ((uint32_t)(freq / SX127x_FREQ_STEP))
|
||||||
#define FREQ_HZ_TO_REG_VAL_24(freq) ((uint32_t)(freq / SX1280_FREQ_STEP))
|
#define FREQ_HZ_TO_REG_VAL_24(freq) ((uint32_t)(freq / SX1280_FREQ_STEP))
|
||||||
|
|
||||||
#define ELRS_RATE_MAX 4
|
#define ELRS_RATE_MAX_24 6
|
||||||
#define ELRS_BINDING_RATE_24 3
|
#define ELRS_RATE_MAX_900 4
|
||||||
|
#define ELRS_RATE_MAX ((ELRS_RATE_MAX_24 > ELRS_RATE_MAX_900) ? ELRS_RATE_MAX_24 : ELRS_RATE_MAX_900)
|
||||||
|
#define ELRS_BINDING_RATE_24 5
|
||||||
#define ELRS_BINDING_RATE_900 2
|
#define ELRS_BINDING_RATE_900 2
|
||||||
|
|
||||||
#define ELRS_MAX_CHANNELS 16
|
#define ELRS_MAX_CHANNELS 16
|
||||||
|
@ -121,8 +123,15 @@ typedef enum {
|
||||||
RATE_FLRC_1000HZ,
|
RATE_FLRC_1000HZ,
|
||||||
} elrsRfRate_e; // Max value of 16 since only 4 bits have been assigned in the sync package.
|
} elrsRfRate_e; // Max value of 16 since only 4 bits have been assigned in the sync package.
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
RADIO_TYPE_SX127x_LORA,
|
||||||
|
RADIO_TYPE_SX128x_LORA,
|
||||||
|
RADIO_TYPE_SX128x_FLRC,
|
||||||
|
} elrsRadioType_e;
|
||||||
|
|
||||||
typedef struct elrsModSettings_s {
|
typedef struct elrsModSettings_s {
|
||||||
uint8_t index;
|
uint8_t index;
|
||||||
|
elrsRadioType_e radioType; // elrsRadioType_e
|
||||||
elrsRfRate_e enumRate; // Max value of 16 since only 4 bits have been assigned in the sync package.
|
elrsRfRate_e enumRate; // Max value of 16 since only 4 bits have been assigned in the sync package.
|
||||||
uint8_t bw;
|
uint8_t bw;
|
||||||
uint8_t sf;
|
uint8_t sf;
|
||||||
|
@ -202,7 +211,9 @@ typedef struct elrsOtaPacket_s {
|
||||||
} __attribute__ ((__packed__)) elrsOtaPacket_t;
|
} __attribute__ ((__packed__)) elrsOtaPacket_t;
|
||||||
|
|
||||||
typedef bool (*elrsRxInitFnPtr)(IO_t resetPin, IO_t busyPin);
|
typedef bool (*elrsRxInitFnPtr)(IO_t resetPin, IO_t busyPin);
|
||||||
typedef void (*elrsRxConfigFnPtr)(const uint8_t bw, const uint8_t sf, const uint8_t cr, const uint32_t freq, const uint8_t preambleLen, const bool iqInverted);
|
typedef void (*elrsRxConfigFnPtr)(const uint8_t bw, const uint8_t sfbt, const uint8_t cr,
|
||||||
|
const uint32_t freq, const uint8_t preambleLength, const bool iqInverted,
|
||||||
|
const uint32_t flrcSyncWord, const uint16_t flrcCrcSeed, const bool isFlrc);
|
||||||
typedef void (*elrsRxStartReceivingFnPtr)(void);
|
typedef void (*elrsRxStartReceivingFnPtr)(void);
|
||||||
typedef void (*elrsRxISRFnPtr)(void);
|
typedef void (*elrsRxISRFnPtr)(void);
|
||||||
typedef void (*elrsRxHandleFromTockFnPtr)(void);
|
typedef void (*elrsRxHandleFromTockFnPtr)(void);
|
||||||
|
@ -211,7 +222,7 @@ typedef void (*elrsRxTransmitDataFnPtr)(const uint8_t *data, const uint8_t lengt
|
||||||
typedef void (*elrsRxReceiveDataFnPtr)(uint8_t *data, const uint8_t length);
|
typedef void (*elrsRxReceiveDataFnPtr)(uint8_t *data, const uint8_t length);
|
||||||
typedef void (*elrsRxgetRfLinkInfoFnPtr)(int8_t *rssi, int8_t *snr);
|
typedef void (*elrsRxgetRfLinkInfoFnPtr)(int8_t *rssi, int8_t *snr);
|
||||||
typedef void (*elrsRxSetFrequencyFnPtr)(const uint32_t freq);
|
typedef void (*elrsRxSetFrequencyFnPtr)(const uint32_t freq);
|
||||||
typedef void (*elrsRxHandleFreqCorrectionFnPtr)(int32_t offset, const uint32_t freq);
|
typedef void (*elrsRxHandleFreqCorrectionFnPtr)(int32_t *offset, const uint32_t freq);
|
||||||
|
|
||||||
extern elrsModSettings_t airRateConfig[][ELRS_RATE_MAX];
|
extern elrsModSettings_t airRateConfig[][ELRS_RATE_MAX];
|
||||||
extern elrsRfPerfParams_t rfPerfConfig[][ELRS_RATE_MAX];
|
extern elrsRfPerfParams_t rfPerfConfig[][ELRS_RATE_MAX];
|
||||||
|
@ -224,11 +235,11 @@ uint8_t fhssGetNumEntries(void);
|
||||||
uint8_t fhssGetCurrIndex(void);
|
uint8_t fhssGetCurrIndex(void);
|
||||||
void fhssSetCurrIndex(const uint8_t value);
|
void fhssSetCurrIndex(const uint8_t value);
|
||||||
uint32_t fhssGetNextFreq(const int32_t freqCorrection);
|
uint32_t fhssGetNextFreq(const int32_t freqCorrection);
|
||||||
void fhssGenSequence(const uint8_t UID[], const elrsFreqDomain_e dom);
|
void fhssGenSequence(const uint32_t uidSeed, const elrsFreqDomain_e dom);
|
||||||
uint8_t tlmRatioEnumToValue(const elrsTlmRatio_e enumval);
|
uint8_t tlmRatioEnumToValue(const elrsTlmRatio_e enumval);
|
||||||
uint16_t rateEnumToHz(const elrsRfRate_e eRate);
|
uint16_t rateEnumToHz(const elrsRfRate_e eRate);
|
||||||
uint16_t txPowerIndexToValue(const uint8_t index);
|
uint16_t txPowerIndexToValue(const uint8_t index);
|
||||||
|
uint32_t elrsUidToSeed(const uint8_t UID[]);
|
||||||
//
|
//
|
||||||
// Link Quality
|
// Link Quality
|
||||||
//
|
//
|
||||||
|
|
|
@ -32,10 +32,10 @@ typedef enum {
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
ELRS_DIO_UNKNOWN = 0,
|
ELRS_DIO_UNKNOWN = 0,
|
||||||
ELRS_DIO_RX_DONE = 1,
|
ELRS_DIO_RX_DONE = (1 << 0),
|
||||||
ELRS_DIO_TX_DONE = 2,
|
ELRS_DIO_TX_DONE = (1 << 1),
|
||||||
ELRS_DIO_RX_AND_TX_DONE = 3,
|
ELRS_DIO_HWERROR = (1 << 2),
|
||||||
} dioReason_e;
|
} dioReasonFlags_e;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
ELRS_CONNECTED,
|
ELRS_CONNECTED,
|
||||||
|
@ -87,6 +87,7 @@ typedef struct elrsReceiver_s {
|
||||||
uint32_t rfModeCycledAtMs;
|
uint32_t rfModeCycledAtMs;
|
||||||
uint8_t rateIndex;
|
uint8_t rateIndex;
|
||||||
uint8_t nextRateIndex;
|
uint8_t nextRateIndex;
|
||||||
|
uint8_t switchMode;
|
||||||
|
|
||||||
uint32_t gotConnectionMs;
|
uint32_t gotConnectionMs;
|
||||||
uint32_t lastSyncPacketMs;
|
uint32_t lastSyncPacketMs;
|
||||||
|
@ -98,7 +99,6 @@ typedef struct elrsReceiver_s {
|
||||||
bool inBindingMode;
|
bool inBindingMode;
|
||||||
volatile bool initializeReceiverPending;
|
volatile bool initializeReceiverPending;
|
||||||
volatile bool fhssRequired;
|
volatile bool fhssRequired;
|
||||||
volatile bool didFhss;
|
|
||||||
|
|
||||||
uint32_t statsUpdatedAtMs;
|
uint32_t statsUpdatedAtMs;
|
||||||
|
|
||||||
|
|
|
@ -122,6 +122,7 @@ static void printFhssSequence(uint8_t *seq)
|
||||||
TEST(RxSpiExpressLrsUnitTest, TestFHSSTable)
|
TEST(RxSpiExpressLrsUnitTest, TestFHSSTable)
|
||||||
{
|
{
|
||||||
const uint8_t UID[6] = {1, 2, 3, 4, 5, 6};
|
const uint8_t UID[6] = {1, 2, 3, 4, 5, 6};
|
||||||
|
const uint32_t seed = elrsUidToSeed(UID);
|
||||||
|
|
||||||
const uint8_t expectedSequence[2][ELRS_NR_SEQUENCE_ENTRIES] = {
|
const uint8_t expectedSequence[2][ELRS_NR_SEQUENCE_ENTRIES] = {
|
||||||
{
|
{
|
||||||
|
@ -178,7 +179,7 @@ TEST(RxSpiExpressLrsUnitTest, TestFHSSTable)
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
fhssGenSequence(UID, ISM2400);
|
fhssGenSequence(seed, ISM2400);
|
||||||
if (PRINT_FHSS_SEQUENCES) {
|
if (PRINT_FHSS_SEQUENCES) {
|
||||||
printFhssSequence(fhssSequence);
|
printFhssSequence(fhssSequence);
|
||||||
}
|
}
|
||||||
|
@ -186,7 +187,7 @@ TEST(RxSpiExpressLrsUnitTest, TestFHSSTable)
|
||||||
EXPECT_EQ(expectedSequence[0][i], fhssSequence[i]);
|
EXPECT_EQ(expectedSequence[0][i], fhssSequence[i]);
|
||||||
}
|
}
|
||||||
|
|
||||||
fhssGenSequence(UID, FCC915);
|
fhssGenSequence(seed, FCC915);
|
||||||
if (PRINT_FHSS_SEQUENCES) {
|
if (PRINT_FHSS_SEQUENCES) {
|
||||||
printFhssSequence(fhssSequence);
|
printFhssSequence(fhssSequence);
|
||||||
}
|
}
|
||||||
|
@ -249,23 +250,18 @@ TEST(RxSpiExpressLrsUnitTest, TestInitUnbound)
|
||||||
rxExpressLrsSpiConfigMutable()->rateIndex = 1;
|
rxExpressLrsSpiConfigMutable()->rateIndex = 1;
|
||||||
rxExpressLrsSpiConfigMutable()->domain = ISM2400;
|
rxExpressLrsSpiConfigMutable()->domain = ISM2400;
|
||||||
expressLrsSpiInit(&injectedConfig, &config, &extiConfig);
|
expressLrsSpiInit(&injectedConfig, &config, &extiConfig);
|
||||||
EXPECT_EQ(airRateConfig[1][3].index, receiver.modParams->index);
|
EXPECT_EQ(airRateConfig[1][5].index, receiver.modParams->index);
|
||||||
EXPECT_EQ(airRateConfig[1][3].enumRate, receiver.modParams->enumRate);
|
EXPECT_EQ(airRateConfig[1][5].enumRate, receiver.modParams->enumRate);
|
||||||
EXPECT_EQ(airRateConfig[1][3].bw, receiver.modParams->bw);
|
EXPECT_EQ(airRateConfig[1][5].bw, receiver.modParams->bw);
|
||||||
EXPECT_EQ(airRateConfig[1][3].sf, receiver.modParams->sf);
|
EXPECT_EQ(airRateConfig[1][5].sf, receiver.modParams->sf);
|
||||||
EXPECT_EQ(airRateConfig[1][3].cr, receiver.modParams->cr);
|
EXPECT_EQ(airRateConfig[1][5].cr, receiver.modParams->cr);
|
||||||
EXPECT_EQ(airRateConfig[1][3].interval, receiver.modParams->interval);
|
EXPECT_EQ(airRateConfig[1][5].interval, receiver.modParams->interval);
|
||||||
EXPECT_EQ(airRateConfig[1][3].tlmInterval, receiver.modParams->tlmInterval);
|
EXPECT_EQ(airRateConfig[1][5].tlmInterval, receiver.modParams->tlmInterval);
|
||||||
EXPECT_EQ(airRateConfig[1][3].fhssHopInterval, receiver.modParams->fhssHopInterval);
|
EXPECT_EQ(airRateConfig[1][5].fhssHopInterval, receiver.modParams->fhssHopInterval);
|
||||||
EXPECT_EQ(airRateConfig[1][3].preambleLen, receiver.modParams->preambleLen);
|
EXPECT_EQ(airRateConfig[1][5].preambleLen, receiver.modParams->preambleLen);
|
||||||
|
|
||||||
//check switch mode
|
//check switch mode
|
||||||
receiver = empty;
|
receiver = empty;
|
||||||
rxExpressLrsSpiConfigMutable()->switchMode = SM_HYBRID;
|
|
||||||
expressLrsSpiInit(&injectedConfig, &config, &extiConfig);
|
|
||||||
EXPECT_EQ(16, config.channelCount);
|
|
||||||
receiver = empty;
|
|
||||||
rxExpressLrsSpiConfigMutable()->switchMode = SM_WIDE;
|
|
||||||
expressLrsSpiInit(&injectedConfig, &config, &extiConfig);
|
expressLrsSpiInit(&injectedConfig, &config, &extiConfig);
|
||||||
EXPECT_EQ(16, config.channelCount);
|
EXPECT_EQ(16, config.channelCount);
|
||||||
}
|
}
|
||||||
|
@ -277,7 +273,7 @@ TEST(RxSpiExpressLrsUnitTest, TestInitBound)
|
||||||
memcpy(rxExpressLrsSpiConfigMutable()->UID, validUID, 6);
|
memcpy(rxExpressLrsSpiConfigMutable()->UID, validUID, 6);
|
||||||
|
|
||||||
// check mod params
|
// check mod params
|
||||||
for (int i = 0; i < ELRS_RATE_MAX; i++) {
|
for (int i = 0; i < ELRS_RATE_MAX_900; i++) {
|
||||||
receiver = empty;
|
receiver = empty;
|
||||||
rxExpressLrsSpiConfigMutable()->rateIndex = i;
|
rxExpressLrsSpiConfigMutable()->rateIndex = i;
|
||||||
rxExpressLrsSpiConfigMutable()->domain = FCC915;
|
rxExpressLrsSpiConfigMutable()->domain = FCC915;
|
||||||
|
@ -291,7 +287,9 @@ TEST(RxSpiExpressLrsUnitTest, TestInitBound)
|
||||||
EXPECT_EQ(airRateConfig[0][i].tlmInterval, receiver.modParams->tlmInterval);
|
EXPECT_EQ(airRateConfig[0][i].tlmInterval, receiver.modParams->tlmInterval);
|
||||||
EXPECT_EQ(airRateConfig[0][i].fhssHopInterval, receiver.modParams->fhssHopInterval);
|
EXPECT_EQ(airRateConfig[0][i].fhssHopInterval, receiver.modParams->fhssHopInterval);
|
||||||
EXPECT_EQ(airRateConfig[0][i].preambleLen, receiver.modParams->preambleLen);
|
EXPECT_EQ(airRateConfig[0][i].preambleLen, receiver.modParams->preambleLen);
|
||||||
|
}
|
||||||
|
|
||||||
|
for (int i = 0; i < ELRS_RATE_MAX_24; i++) {
|
||||||
receiver = empty;
|
receiver = empty;
|
||||||
rxExpressLrsSpiConfigMutable()->rateIndex = i;
|
rxExpressLrsSpiConfigMutable()->rateIndex = i;
|
||||||
rxExpressLrsSpiConfigMutable()->domain = ISM2400;
|
rxExpressLrsSpiConfigMutable()->domain = ISM2400;
|
||||||
|
@ -416,7 +414,9 @@ extern "C" {
|
||||||
bool rxSpiExtiConfigured(void) { return true; }
|
bool rxSpiExtiConfigured(void) { return true; }
|
||||||
|
|
||||||
bool sx1280IsBusy(void) { return false; }
|
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 sx1280Config(const uint8_t /* bw */, const uint8_t /* sfbt */, const uint8_t /* cr */,
|
||||||
|
const uint32_t /* freq */, const uint8_t /* preambleLength */, const bool /* iqInverted */,
|
||||||
|
const uint32_t /* flrcSyncWord */, const uint16_t /* flrcCrcSeed */, const bool /* isFlrc */) {}
|
||||||
void sx1280StartReceiving(void) {}
|
void sx1280StartReceiving(void) {}
|
||||||
void sx1280ISR(void) {}
|
void sx1280ISR(void) {}
|
||||||
bool rxSpiGetExtiState(void) { return false; }
|
bool rxSpiGetExtiState(void) { return false; }
|
||||||
|
@ -430,11 +430,13 @@ extern "C" {
|
||||||
*rssi = 0;
|
*rssi = 0;
|
||||||
*snr = 0;
|
*snr = 0;
|
||||||
}
|
}
|
||||||
void sx1280AdjustFrequency(int32_t , const uint32_t ) {}
|
void sx1280AdjustFrequency(int32_t *, const uint32_t ) {}
|
||||||
bool sx1280Init(IO_t , IO_t ) { return true; }
|
bool sx1280Init(IO_t , IO_t ) { return true; }
|
||||||
void sx1280SetOutputPower(const int8_t ) {}
|
void sx1280SetOutputPower(const int8_t ) {}
|
||||||
|
|
||||||
void sx127xConfig(const sx127xBandwidth_e , const sx127xSpreadingFactor_e , const sx127xCodingRate_e , const uint32_t , const uint8_t , const bool ) {}
|
void sx127xConfig(const uint8_t /* bw */, const uint8_t /* sfbt */, const uint8_t /* cr */,
|
||||||
|
const uint32_t /* freq */, const uint8_t /* preambleLength */, const bool /* iqInverted */,
|
||||||
|
const uint32_t /* flrcSyncWord */, const uint16_t /* flrcCrcSeed */, const bool /* isFlrc */) {}
|
||||||
void sx127xStartReceiving(void) {}
|
void sx127xStartReceiving(void) {}
|
||||||
uint8_t sx127xISR(uint32_t *timestamp)
|
uint8_t sx127xISR(uint32_t *timestamp)
|
||||||
{
|
{
|
||||||
|
@ -449,7 +451,7 @@ extern "C" {
|
||||||
*rssi = 0;
|
*rssi = 0;
|
||||||
*snr = 0;
|
*snr = 0;
|
||||||
}
|
}
|
||||||
void sx127xAdjustFrequency(int32_t , const uint32_t ) {}
|
void sx127xAdjustFrequency(int32_t *, const uint32_t ) {}
|
||||||
bool sx127xInit(IO_t , IO_t ) { return true; }
|
bool sx127xInit(IO_t , IO_t ) { return true; }
|
||||||
|
|
||||||
int scaleRange(int x, int srcFrom, int srcTo, int destFrom, int destTo) {
|
int scaleRange(int x, int srcFrom, int srcTo, int destFrom, int destTo) {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue