Skip to content

Commit 2d5dc5c

Browse files
authored
Force binding at 50Hz (ExpressLRS#1057)
* Force binding at 50Hz * Indicate that binding mode ends when entering wifi
1 parent eb2316e commit 2d5dc5c

4 files changed

Lines changed: 79 additions & 57 deletions

File tree

src/include/common.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -105,6 +105,7 @@ typedef struct expresslrs_rf_pref_params_s
105105
#if defined(Regulatory_Domain_AU_915) || defined(Regulatory_Domain_EU_868) || defined(Regulatory_Domain_IN_866) || defined(Regulatory_Domain_FCC_915) || defined(Regulatory_Domain_AU_433) || defined(Regulatory_Domain_EU_433)
106106
#define RATE_MAX 4
107107
#define RATE_DEFAULT 0
108+
#define RATE_BINDING 2 // 50Hz bind mode
108109
typedef struct expresslrs_mod_settings_s
109110
{
110111
int8_t index;
@@ -124,6 +125,7 @@ typedef struct expresslrs_mod_settings_s
124125
#if defined(Regulatory_Domain_ISM_2400)
125126
#define RATE_MAX 4
126127
#define RATE_DEFAULT 0
128+
#define RATE_BINDING 3 // 50Hz bind mode
127129
typedef struct expresslrs_mod_settings_s
128130
{
129131
int8_t index;

src/lib/WIFI/devWIFI.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -722,8 +722,13 @@ static int timeout()
722722
if (!webserverPreventAutoStart && (connectionState == disconnected))
723723
{
724724
static bool pastAutoInterval = false;
725+
// If InBindingMode then wait at least 60 seconds before going into wifi,
726+
// regardless of if AUTO_WIFI_ON_INTERVAL is set to less
725727
if (!InBindingMode || AUTO_WIFI_ON_INTERVAL >= 60 || pastAutoInterval)
726728
{
729+
// No need to ExitBindingMode(), the radio is about to be stopped. Need
730+
// to change this before the mode change event so the LED is updated
731+
InBindingMode = false;
727732
connectionState = wifiUpdate;
728733
return DURATION_IMMEDIATELY;
729734
}

src/src/rx_main.cpp

Lines changed: 63 additions & 48 deletions
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,7 @@ extern bool webserverPreventAutoStart;
7676
#endif
7777

7878
#if defined(GPIO_PIN_PWM_OUTPUTS)
79-
#include <Servo.h>
79+
#include <Servo.h>
8080
static constexpr uint8_t SERVO_PINS[] = GPIO_PIN_PWM_OUTPUTS;
8181
static constexpr uint8_t SERVO_COUNT = ARRAY_SIZE(SERVO_PINS);
8282
static Servo *Servos[SERVO_COUNT];
@@ -670,6 +670,14 @@ static void ICACHE_RAM_ATTR MspReceiveComplete()
670670

671671
static void ICACHE_RAM_ATTR ProcessRfPacket_MSP()
672672
{
673+
// Always examine MSP packets for bind information if in bind mode
674+
// [1] is the package index, first packet of the MSP
675+
if (InBindingMode && Radio.RXdataBuffer[1] == 1 && Radio.RXdataBuffer[2] == MSP_ELRS_BIND)
676+
{
677+
OnELRSBindMSP((uint8_t *)&Radio.RXdataBuffer[2]);
678+
return;
679+
}
680+
673681
// Must be fully connected to process MSP, prevents processing MSP
674682
// during sync, where packets can be received before connection
675683
if (connectionState != connected)
@@ -681,13 +689,7 @@ static void ICACHE_RAM_ATTR ProcessRfPacket_MSP()
681689
{
682690
NextTelemetryType = ELRS_TELEMETRY_TYPE_LINK;
683691
}
684-
685-
if (Radio.RXdataBuffer[1] == 1 && MspData[0] == MSP_ELRS_BIND)
686-
{
687-
OnELRSBindMSP(MspData);
688-
MspReceiver.ResetState();
689-
}
690-
else if (MspReceiver.HasFinishedData())
692+
if (MspReceiver.HasFinishedData())
691693
{
692694
MspReceiveComplete();
693695
}
@@ -753,8 +755,8 @@ void ICACHE_RAM_ATTR ProcessRFPacket()
753755
uint16_t inCRC = (((uint16_t)(Radio.RXdataBuffer[0] & 0b11111100)) << 6) | Radio.RXdataBuffer[7];
754756

755757
// For smHybrid the CRC only has the packet type in byte 0
756-
// For smHybridWide the FHSS slot is added to the CRC in byte 0 except on SYNC packets
757-
if (type == SYNC_PACKET || OtaSwitchModeCurrent != smHybridWide)
758+
// For smHybridWide the FHSS slot is added to the CRC in byte 0 on RC_DATA_PACKETs
759+
if (type != RC_DATA_PACKET || OtaSwitchModeCurrent != smHybridWide)
758760
{
759761
Radio.RXdataBuffer[0] = type;
760762
}
@@ -797,7 +799,7 @@ void ICACHE_RAM_ATTR ProcessRFPacket()
797799
// not implimented yet
798800
break;
799801
case SYNC_PACKET: //sync packet from master
800-
doStartTimer = ProcessRfPacket_SYNC(now);
802+
doStartTimer = ProcessRfPacket_SYNC(now) && !InBindingMode;
801803
break;
802804
default: // code to be executed if n doesn't match any cases
803805
break;
@@ -1072,7 +1074,7 @@ static void servosUpdate(unsigned long now)
10721074

10731075
if (Servos[ch])
10741076
Servos[ch]->writeMicroseconds(us);
1075-
else if (us >= 988U && us <= 2012U)
1077+
else if (us >= 988U && us <= 2012U)
10761078
{
10771079
// us might be out of bounds if this is a switch channel and it has not been
10781080
// received yet. Delay initializing the servo until the channel is valid
@@ -1104,6 +1106,34 @@ static void servosUpdate(unsigned long now)
11041106
#endif
11051107
}
11061108

1109+
static void updateBindingMode()
1110+
{
1111+
// If the eeprom is indicating that we're not bound
1112+
// and we're not already in binding mode, enter binding
1113+
if (!config.GetIsBound() && !InBindingMode)
1114+
{
1115+
INFOLN("RX has not been bound, enter binding mode...");
1116+
EnterBindingMode();
1117+
}
1118+
// If in binding mode and the bind packet has come in, leave binding mode
1119+
else if (config.GetIsBound() && InBindingMode)
1120+
{
1121+
ExitBindingMode();
1122+
}
1123+
1124+
#ifndef MY_UID
1125+
// If the power on counter is >=3, enter binding and clear counter
1126+
if (config.GetPowerOnCounter() >= 3)
1127+
{
1128+
config.SetPowerOnCounter(0);
1129+
config.Commit();
1130+
1131+
INFOLN("Power on counter >=3, enter binding mode...");
1132+
EnterBindingMode();
1133+
}
1134+
#endif
1135+
}
1136+
11071137
#if defined(PLATFORM_ESP8266)
11081138
// Called from core's user_rf_pre_init() function (which is called by SDK) before setup()
11091139
RF_PRE_INIT()
@@ -1166,7 +1196,6 @@ void loop()
11661196
}
11671197

11681198
devicesUpdate(now);
1169-
servosUpdate(now);
11701199

11711200
#if defined(PLATFORM_ESP8266) && defined(AUTO_WIFI_ON_INTERVAL)
11721201
// If the reboot time is set and the current time is past the reboot time then reboot.
@@ -1175,7 +1204,7 @@ void loop()
11751204
}
11761205
#endif
11771206

1178-
if (connectionState > FAILURE_STATES)
1207+
if (connectionState > MODE_STATES)
11791208
{
11801209
return;
11811210
}
@@ -1198,6 +1227,7 @@ void loop()
11981227
}
11991228

12001229
cycleRfMode(now);
1230+
servosUpdate(now);
12011231

12021232
uint32_t localLastValidPacket = LastValidPacket; // Required to prevent race condition due to LastValidPacket getting updated from ISR
12031233
if ((connectionState == disconnectPending) ||
@@ -1230,33 +1260,14 @@ void loop()
12301260
DBGLN("Timer locked");
12311261
}
12321262

1233-
// If the eeprom is indicating that we're not bound
1234-
// and we're not already in binding mode, enter binding
1235-
if (!config.GetIsBound() && !InBindingMode)
1236-
{
1237-
INFOLN("RX has not been bound, enter binding mode...");
1238-
EnterBindingMode();
1239-
}
1240-
1241-
// If the power on counter is >=3, enter binding and clear counter
1242-
#ifndef MY_UID
1243-
if (config.GetPowerOnCounter() >= 3)
1244-
{
1245-
config.SetPowerOnCounter(0);
1246-
config.Commit();
1247-
1248-
INFOLN("Power on counter >=3, enter binding mode...");
1249-
EnterBindingMode();
1250-
}
1251-
#endif
1252-
12531263
uint8_t *nextPayload = 0;
12541264
uint8_t nextPlayloadSize = 0;
12551265
if (!TelemetrySender.IsActive() && telemetry.GetNextPayload(&nextPlayloadSize, &nextPayload))
12561266
{
12571267
TelemetrySender.SetDataToTransmit(nextPlayloadSize, nextPayload, ELRS_TELEMETRY_BYTES_PER_CALL);
12581268
}
12591269
updateTelemetryBurst();
1270+
updateBindingMode();
12601271
}
12611272

12621273
struct bootloader {
@@ -1310,11 +1321,12 @@ void EnterBindingMode()
13101321
UID[5] = BindingUID[5];
13111322

13121323
CRCInitializer = 0;
1324+
config.SetIsBound(false);
13131325
InBindingMode = true;
13141326

13151327
// Start attempting to bind
13161328
// Lock the RF rate and freq while binding
1317-
SetRFLinkRate(RATE_DEFAULT);
1329+
SetRFLinkRate(RATE_BINDING);
13181330
Radio.SetFrequencyReg(GetInitialFreq());
13191331
// If the Radio Params (including InvertIQ) parameter changed, need to restart RX to take effect
13201332
Radio.RXnb();
@@ -1325,13 +1337,25 @@ void EnterBindingMode()
13251337

13261338
void ExitBindingMode()
13271339
{
1328-
if (!InBindingMode) {
1340+
if (!InBindingMode)
1341+
{
13291342
// Not in binding mode
13301343
DBGLN("Cannot exit binding mode, not in binding mode!");
13311344
return;
13321345
}
13331346

1347+
// Prevent any new packets from coming in
1348+
Radio.SetTxIdleMode();
13341349
LostConnection();
1350+
// Write the values to eeprom
1351+
config.Commit();
1352+
1353+
CRCInitializer = (UID[4] << 8) | UID[5];
1354+
FHSSrandomiseFHSSsequence(uidMacSeedGet());
1355+
1356+
#if defined(PLATFORM_ESP32) || defined(PLATFORM_ESP8266)
1357+
webserverPreventAutoStart = true;
1358+
#endif
13351359

13361360
// Force RF cycling to start at the beginning immediately
13371361
scanIndex = RATE_MAX;
@@ -1340,18 +1364,17 @@ void ExitBindingMode()
13401364
// Do this last as LostConnection() will wait for a tock that never comes
13411365
// if we're in binding mode
13421366
InBindingMode = false;
1367+
DBGLN("Exiting binding mode");
13431368
devicesTriggerEvent();
13441369
}
13451370

1346-
void OnELRSBindMSP(uint8_t* packet)
1371+
void ICACHE_RAM_ATTR OnELRSBindMSP(uint8_t* packet)
13471372
{
13481373
for (int i = 1; i <=4; i++)
13491374
{
13501375
UID[i + 1] = packet[i];
13511376
}
13521377

1353-
CRCInitializer = (UID[4] << 8) | UID[5];
1354-
13551378
DBGLN("New UID = %d, %d, %d, %d, %d, %d", UID[0], UID[1], UID[2], UID[3], UID[4], UID[5]);
13561379

13571380
// Set new UID in eeprom
@@ -1360,15 +1383,7 @@ void OnELRSBindMSP(uint8_t* packet)
13601383
// Set eeprom byte to indicate RX is bound
13611384
config.SetIsBound(true);
13621385

1363-
// Write the values to eeprom
1364-
config.Commit();
1365-
1366-
FHSSrandomiseFHSSsequence(uidMacSeedGet());
1367-
1368-
#if defined(PLATFORM_ESP32) || defined(PLATFORM_ESP8266)
1369-
webserverPreventAutoStart = true;
1370-
#endif
1371-
ExitBindingMode();
1386+
// EEPROM commit will happen on the main thread in ExitBindingMode()
13721387
}
13731388

13741389
void UpdateModelMatch(uint8_t model)

src/src/tx_main.cpp

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,7 @@ volatile bool connectionHasModelMatch = true;
7979

8080
bool InBindingMode = false;
8181
uint8_t MSPDataPackage[5];
82-
uint8_t BindingSendCount = 0;
82+
static uint8_t BindingSendCount;
8383
bool RxWiFiReadyToSend = false;
8484
#if defined(USE_TX_BACKPACK)
8585
bool TxBackpackWiFiReadyToSend = false;
@@ -351,7 +351,7 @@ void ICACHE_RAM_ATTR SetRFLinkRate(uint8_t index) // Set speed of RF link (hz)
351351
&& (invertIQ == Radio.IQinverted))
352352
return;
353353

354-
DBGLN("set rate");
354+
DBGLN("set rate %u", index);
355355
hwTimer.updateInterval(ModParams->interval);
356356
Radio.Config(ModParams->bw, ModParams->sf, ModParams->cr, GetInitialFreq(), ModParams->PreambleLen, invertIQ, ModParams->PayloadLength);
357357

@@ -391,10 +391,10 @@ void ICACHE_RAM_ATTR SendRCdataToRF()
391391
static uint8_t syncSlot;
392392
#if defined(NO_SYNC_ON_ARM)
393393
uint32_t SyncInterval = 250;
394-
bool skipSync = IsArmed();
394+
bool skipSync = IsArmed() || InBindingMode;
395395
#else
396396
uint32_t SyncInterval = (connectionState == connected) ? ExpressLRS_currAirRate_RFperfParams->SyncPktIntervalConnected : ExpressLRS_currAirRate_RFperfParams->SyncPktIntervalDisconnected;
397-
bool skipSync = false;
397+
bool skipSync = InBindingMode;
398398
#endif
399399

400400
uint8_t NonceFHSSresult = NonceTX % ExpressLRS_currAirRate_Modparams->FHSShopInterval;
@@ -447,7 +447,7 @@ void ICACHE_RAM_ATTR SendRCdataToRF()
447447
}
448448

449449
// artificially inject the low bits of the nonce on data packets, this will be overwritten with the CRC after it's calculated
450-
if (Radio.TXdataBuffer[0] != SYNC_PACKET && OtaSwitchModeCurrent == smHybridWide)
450+
if (Radio.TXdataBuffer[0] == RC_DATA_PACKET && OtaSwitchModeCurrent == smHybridWide)
451451
Radio.TXdataBuffer[0] |= NonceFHSSresult << 2;
452452

453453
///// Next, Calculate the CRC and put it into the buffer /////
@@ -469,7 +469,8 @@ void ICACHE_RAM_ATTR timerCallbackNormal()
469469
#endif
470470

471471
// Nonce advances on every timer tick
472-
NonceTX++;
472+
if (!InBindingMode)
473+
NonceTX++;
473474

474475
// If HandleTLM has started Receive mode, TLM packet reception should begin shortly
475476
// Skip transmitting on this slot
@@ -762,7 +763,6 @@ void SendUIDOverMSP()
762763
MspSender.ResetState();
763764
BindingSendCount = 0;
764765
MspSender.SetDataToTransmit(5, MSPDataPackage, ELRS_MSP_BYTES_PER_CALL);
765-
InBindingMode = true;
766766
}
767767

768768
void EnterBindingMode()
@@ -788,12 +788,12 @@ void EnterBindingMode()
788788
UID[5] = BindingUID[5];
789789

790790
CRCInitializer = 0;
791-
791+
NonceTX = 0; // Lock the NonceTX to prevent syncspam packets
792792
InBindingMode = true;
793793

794794
// Start attempting to bind
795795
// Lock the RF rate and freq while binding
796-
SetRFLinkRate(RATE_DEFAULT);
796+
SetRFLinkRate(RATE_BINDING);
797797
Radio.SetFrequencyReg(GetInitialFreq());
798798
// Start transmitting again
799799
hwTimer.resume();

0 commit comments

Comments
 (0)