Skip to content

Commit 9e1979f

Browse files
authored
Update Lua bandwidth indicator to account for TLM Burst (ExpressLRS#1516)
* Update TLM bandwidth calc to account for burst * Split updateFolderName, remove redundant calls
1 parent 460f5af commit 9e1979f

4 files changed

Lines changed: 99 additions & 49 deletions

File tree

src/include/common.h

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -150,8 +150,9 @@ extern SX1280Driver Radio;
150150
expresslrs_mod_settings_s *get_elrs_airRateConfig(uint8_t index);
151151
expresslrs_rf_pref_params_s *get_elrs_RFperfParams(uint8_t index);
152152

153-
uint8_t TLMratioEnumToValue(uint8_t enumval);
154-
uint16_t RateEnumToHz(uint8_t eRate);
153+
uint8_t TLMratioEnumToValue(uint8_t const enumval);
154+
uint8_t TLMBurstMaxForRateRatio(uint16_t const rateHz, uint8_t const ratioDiv);
155+
uint16_t RateEnumToHz(uint8_t const eRate);
155156

156157
extern expresslrs_mod_settings_s *ExpressLRS_currAirRate_Modparams;
157158
extern expresslrs_rf_pref_params_s *ExpressLRS_currAirRate_RFperfParams;

src/lib/LUA/tx_devLUA.cpp

Lines changed: 68 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -264,17 +264,25 @@ static void luadevUpdateModelID() {
264264
strcat(modelMatchUnit,")");
265265
}
266266

267-
static void luadevUpdateTlmBandwidth() {
268-
if((expresslrs_tlm_ratio_e)config.GetTlm()){
269-
tlmBandwidth[0] = ' ';
270-
uint32_t hz = RateEnumToHz(ExpressLRS_currAirRate_Modparams->enum_rate);
271-
uint32_t tlmRatio = TLMratioEnumToValue((expresslrs_tlm_ratio_e)config.GetTlm());
272-
uint32_t bandwidthValue = ((float)hz / tlmRatio) *1/2*5*8;
273-
itoa(bandwidthValue,tlmBandwidth+2,10);
274-
strcat(tlmBandwidth,"bps)");
275-
} else {
267+
static void luadevUpdateTlmBandwidth()
268+
{
269+
expresslrs_tlm_ratio_e eRatio = (expresslrs_tlm_ratio_e)config.GetTlm();
270+
if (eRatio == TLM_RATIO_NO_TLM)
271+
{
276272
tlmBandwidth[0] = '\0';
277273
}
274+
else
275+
{
276+
tlmBandwidth[0] = ' ';
277+
278+
uint16_t hz = RateEnumToHz(ExpressLRS_currAirRate_Modparams->enum_rate);
279+
uint8_t ratiodiv = TLMratioEnumToValue(eRatio);
280+
uint8_t burst = TLMBurstMaxForRateRatio(hz, ratiodiv);
281+
uint32_t bandwidthValue = ELRS_TELEMETRY_BYTES_PER_CALL * 8U * burst * hz / ratiodiv / (burst + 1);
282+
283+
itoa(bandwidthValue, &tlmBandwidth[2], 10);
284+
strcat(tlmBandwidth, "bps)");
285+
}
278286
}
279287

280288
static void luadevGeneratePowerOpts()
@@ -395,57 +403,86 @@ static void luahandSimpleSendCmd(struct luaPropertiesCommon *item, uint8_t arg)
395403
}
396404
}
397405

398-
static void updateFolderName(){
399-
400-
//power folder name
406+
static void updateFolderName_TxPower()
407+
{
401408
uint8_t txPwrDyn = config.GetDynamicPower() ? config.GetBoostChannel() + 1 : 0;
402-
uint8_t pwrFolderLabelOffset = getSeparatorIndex(2,pwrFolderDynamicName); // start writing name after the 2nd space
409+
uint8_t pwrFolderLabelOffset = getSeparatorIndex(2, pwrFolderDynamicName); // start writing name after the 2nd space
410+
411+
// Power Level
403412
pwrFolderDynamicName[pwrFolderLabelOffset++] = '(';
404413
pwrFolderLabelOffset += findLuaSelectionLabel(&luaPower, &pwrFolderDynamicName[pwrFolderLabelOffset], config.GetPower() - MinPower);
405-
if(txPwrDyn){
414+
415+
// Dynamic Power
416+
if (txPwrDyn)
417+
{
406418
pwrFolderDynamicName[pwrFolderLabelOffset++] = folderNameSeparator[0];
407419
pwrFolderLabelOffset += findLuaSelectionLabel(&luaDynamicPower, &pwrFolderDynamicName[pwrFolderLabelOffset], txPwrDyn);
408420
}
421+
409422
pwrFolderDynamicName[pwrFolderLabelOffset++] = ')';
410423
pwrFolderDynamicName[pwrFolderLabelOffset] = '\0';
411-
//vtx folder
424+
}
425+
426+
static void updateFolderName_VtxAdmin()
427+
{
412428
uint8_t vtxBand = config.GetVtxBand();
413-
if(vtxBand){
429+
if (vtxBand)
430+
{
414431
luaVtxFolder.dyn_name = vtxFolderDynamicName;
415432
uint8_t vtxFolderLabelOffset = getSeparatorIndex(2,vtxFolderDynamicName); // start writing name after the 2nd space
416433
vtxFolderDynamicName[vtxFolderLabelOffset++] = '(';
434+
435+
// Band
417436
vtxFolderLabelOffset += findLuaSelectionLabel(&luaVtxBand, &vtxFolderDynamicName[vtxFolderLabelOffset], vtxBand);
418437
vtxFolderDynamicName[vtxFolderLabelOffset++] = folderNameSeparator[1];
438+
439+
// Channel
419440
vtxFolderLabelOffset += findLuaSelectionLabel(&luaVtxChannel, &vtxFolderDynamicName[vtxFolderLabelOffset], config.GetVtxChannel());
441+
442+
// VTX Power
420443
uint8_t vtxPwr = config.GetVtxPower();
421444
//if power is no-change (-), don't show, also hide pitmode
422-
if(vtxPwr){
445+
if (vtxPwr)
446+
{
423447
vtxFolderDynamicName[vtxFolderLabelOffset++] = folderNameSeparator[1];
424448
vtxFolderLabelOffset += findLuaSelectionLabel(&luaVtxPwr, &vtxFolderDynamicName[vtxFolderLabelOffset], vtxPwr);
425-
449+
450+
// Pit Mode
426451
uint8_t vtxPit = config.GetVtxPitmode();
427452
//if pitmode is off, don't show
428453
//show pitmode AuxSwitch or show P if not OFF
429-
if(vtxPit != 0){
430-
if(vtxPit != 1){
454+
if (vtxPit != 0)
455+
{
456+
if (vtxPit != 1)
457+
{
431458
vtxFolderDynamicName[vtxFolderLabelOffset++] = folderNameSeparator[1];
432459
vtxFolderLabelOffset += findLuaSelectionLabel(&luaVtxPit, &vtxFolderDynamicName[vtxFolderLabelOffset], vtxPit);
433-
} else {
460+
}
461+
else
462+
{
434463
vtxFolderDynamicName[vtxFolderLabelOffset++] = folderNameSeparator[1];
435464
vtxFolderDynamicName[vtxFolderLabelOffset++] = 'P';
436465
}
437466
}
438467
}
439468
vtxFolderDynamicName[vtxFolderLabelOffset++] = ')';
440469
vtxFolderDynamicName[vtxFolderLabelOffset] = '\0';
441-
} else {
442-
//don't show vtx settings if band is OFF
470+
}
471+
else
472+
{
473+
//don't show vtx settings if band is OFF
443474
luaVtxFolder.dyn_name = NULL;
444475
}
445476
}
446477

478+
static void updateFolderNames()
479+
{
480+
updateFolderName_TxPower();
481+
updateFolderName_VtxAdmin();
482+
}
483+
447484
static void registerLuaParameters()
448-
{
485+
{
449486
registerLUAParameter(&luaAirRate, [](struct luaPropertiesCommon *item, uint8_t arg) {
450487
if ((arg < RATE_MAX) && (arg >= 0))
451488
{
@@ -500,12 +537,12 @@ static void registerLuaParameters()
500537
luadevGeneratePowerOpts();
501538
registerLUAParameter(&luaPower, [](struct luaPropertiesCommon *item, uint8_t arg) {
502539
config.SetPower((PowerLevels_e)constrain(arg + MinPower, MinPower, MaxPower));
503-
updateFolderName();
540+
updateFolderName_TxPower();
504541
}, luaPowerFolder.common.id);
505542
registerLUAParameter(&luaDynamicPower, [](struct luaPropertiesCommon *item, uint8_t arg) {
506543
config.SetDynamicPower(arg > 0);
507544
config.SetBoostChannel((arg - 1) > 0 ? arg - 1 : 0);
508-
updateFolderName();
545+
updateFolderName_TxPower();
509546
}, luaPowerFolder.common.id);
510547
#if defined(GPIO_PIN_FAN_EN)
511548
registerLUAParameter(&luaFanThreshold, [](struct luaPropertiesCommon *item, uint8_t arg){
@@ -519,19 +556,19 @@ static void registerLuaParameters()
519556
registerLUAParameter(&luaVtxFolder);
520557
registerLUAParameter(&luaVtxBand, [](struct luaPropertiesCommon *item, uint8_t arg) {
521558
config.SetVtxBand(arg);
522-
updateFolderName();
559+
updateFolderName_VtxAdmin();
523560
}, luaVtxFolder.common.id);
524561
registerLUAParameter(&luaVtxChannel, [](struct luaPropertiesCommon *item, uint8_t arg) {
525562
config.SetVtxChannel(arg);
526-
updateFolderName();
563+
updateFolderName_VtxAdmin();
527564
}, luaVtxFolder.common.id);
528565
registerLUAParameter(&luaVtxPwr, [](struct luaPropertiesCommon *item, uint8_t arg) {
529566
config.SetVtxPower(arg);
530-
updateFolderName();
567+
updateFolderName_VtxAdmin();
531568
}, luaVtxFolder.common.id);
532569
registerLUAParameter(&luaVtxPit, [](struct luaPropertiesCommon *item, uint8_t arg) {
533570
config.SetVtxPitmode(arg);
534-
updateFolderName();
571+
updateFolderName_VtxAdmin();
535572
}, luaVtxFolder.common.id);
536573
registerLUAParameter(&luaVtxSend, &luahandSimpleSendCmd, luaVtxFolder.common.id);
537574
// WIFI folder
@@ -596,17 +633,14 @@ static int timeout()
596633
static int start()
597634
{
598635
CRSF::RecvParameterUpdate = &luaParamUpdateReq;
599-
luadevUpdateModelID();
600-
luadevUpdateRateSensitivity();
601-
luadevUpdateTlmBandwidth();
602636
registerLuaParameters();
603637
registerLUAPopulateParams([](){
604638
itoa(CRSF::BadPktsCountResult, luaBadGoodString, 10);
605639
strcat(luaBadGoodString, "/");
606640
itoa(CRSF::GoodPktsCountResult, luaBadGoodString + strlen(luaBadGoodString), 10);
607641
setLuaStringValue(&luaInfo, luaBadGoodString);
608642
});
609-
updateFolderName();
643+
updateFolderNames();
610644
event();
611645
return DURATION_IMMEDIATELY;
612646
}

src/src/common.cpp

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -132,6 +132,33 @@ uint8_t ICACHE_RAM_ATTR TLMratioEnumToValue(uint8_t const enumval)
132132
}
133133
}
134134

135+
/***
136+
* @brief: Calculate number of 'burst' telemetry frames for the specified air rate and tlm ratio
137+
*
138+
* When attempting to send a LinkStats telemetry frame at most every TELEM_MIN_LINK_INTERVAL_MS,
139+
* calculate the number of sequential advanced telemetry frames before another LinkStats is due.
140+
****/
141+
uint8_t TLMBurstMaxForRateRatio(uint16_t const rateHz, uint8_t const ratioDiv)
142+
{
143+
// Maximum ms between LINK_STATISTICS packets for determining burst max
144+
constexpr uint32_t TELEM_MIN_LINK_INTERVAL_MS = 512U;
145+
146+
// telemInterval = 1000 / (hz / ratiodiv);
147+
// burst = TELEM_MIN_LINK_INTERVAL_MS / telemInterval;
148+
// This ^^^ rearranged to preserve precision vvv
149+
uint8_t retVal = TELEM_MIN_LINK_INTERVAL_MS * rateHz / ratioDiv / 1000U;
150+
151+
// Reserve one slot for LINK telemetry
152+
if (retVal > 1)
153+
--retVal;
154+
else
155+
retVal = 1;
156+
//DBGLN("TLMburst: %d", retVal);
157+
158+
return retVal;
159+
}
160+
161+
135162
uint16_t RateEnumToHz(uint8_t const eRate)
136163
{
137164
switch(eRate)

src/src/rx_main.cpp

Lines changed: 1 addition & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -96,8 +96,6 @@ CRSF crsf(CRSF_TX_SERIAL);
9696
StubbornSender TelemetrySender(ELRS_TELEMETRY_MAX_PACKAGES);
9797
static uint8_t telemetryBurstCount;
9898
static uint8_t telemetryBurstMax;
99-
// Maximum ms between LINK_STATISTICS packets for determining burst max
100-
#define TELEM_MIN_LINK_INTERVAL 512U
10199

102100
StubbornReceiver MspReceiver(ELRS_MSP_MAX_PACKAGES);
103101
uint8_t MspData[ELRS_MSP_BUFFER];
@@ -1085,17 +1083,7 @@ static void updateTelemetryBurst()
10851083

10861084
uint32_t hz = RateEnumToHz(ExpressLRS_currAirRate_Modparams->enum_rate);
10871085
uint32_t ratiodiv = TLMratioEnumToValue(ExpressLRS_currAirRate_Modparams->TLMinterval);
1088-
// telemInterval = 1000 / (hz / ratiodiv);
1089-
// burst = TELEM_MIN_LINK_INTERVAL / telemInterval;
1090-
// This ^^^ rearranged to preserve precision vvv
1091-
telemetryBurstMax = TELEM_MIN_LINK_INTERVAL * hz / ratiodiv / 1000U;
1092-
1093-
// Reserve one slot for LINK telemetry
1094-
if (telemetryBurstMax > 1)
1095-
--telemetryBurstMax;
1096-
else
1097-
telemetryBurstMax = 1;
1098-
//DBGLN("TLMburst: %d", telemetryBurstMax);
1086+
telemetryBurstMax = TLMBurstMaxForRateRatio(hz, ratiodiv);
10991087

11001088
// Notify the sender to adjust its expected throughput
11011089
TelemetrySender.UpdateTelemetryRate(hz, ratiodiv, telemetryBurstMax);

0 commit comments

Comments
 (0)