3 #include "rxtx_devLua.h"
5 #include "CRSFHandset.h"
10 #define STR_LUA_ALLAUX "AUX1;AUX2;AUX3;AUX4;AUX5;AUX6;AUX7;AUX8;AUX9;AUX10"
12 #define STR_LUA_ALLAUX_UPDOWN "AUX1" LUASYM_ARROW_UP ";AUX1" LUASYM_ARROW_DN ";AUX2" LUASYM_ARROW_UP ";AUX2" LUASYM_ARROW_DN \
13 ";AUX3" LUASYM_ARROW_UP ";AUX3" LUASYM_ARROW_DN ";AUX4" LUASYM_ARROW_UP ";AUX4" LUASYM_ARROW_DN \
14 ";AUX5" LUASYM_ARROW_UP ";AUX5" LUASYM_ARROW_DN ";AUX6" LUASYM_ARROW_UP ";AUX6" LUASYM_ARROW_DN \
15 ";AUX7" LUASYM_ARROW_UP ";AUX7" LUASYM_ARROW_DN ";AUX8" LUASYM_ARROW_UP ";AUX8" LUASYM_ARROW_DN \
16 ";AUX9" LUASYM_ARROW_UP ";AUX9" LUASYM_ARROW_DN ";AUX10" LUASYM_ARROW_UP ";AUX10" LUASYM_ARROW_DN
18 #if defined(RADIO_SX127X)
19 #define STR_LUA_PACKETRATES \
20 "D50Hz(-112dBm);25Hz(-123dBm);50Hz(-120dBm);100Hz(-117dBm);100Hz Full(-112dBm);200Hz(-112dBm)"
21 #elif defined(RADIO_LR1121)
22 #define STR_LUA_PACKETRATES \
23 "K1000 Full Low Band;DK500 2.4G;200 Full Low Band;250 Low Band;X100 Full;X150;" \
24 "50 2.4G;100 Full 2.4G;150 2.4G;250 2.4G;333 Full 2.4G;500 2.4G;" \
25 "50 Low Band;100 Low Band;100 Full Low Band;200 Low Band"
26 #elif defined(RADIO_SX128X)
27 #define STR_LUA_PACKETRATES \
28 "50Hz(-115dBm);100Hz Full(-112dBm);150Hz(-112dBm);250Hz(-108dBm);333Hz Full(-105dBm);500Hz(-105dBm);" \
29 "D250(-104dBm);D500(-104dBm);F500(-104dBm);F1000(-104dBm)"
31 #error Invalid radio configuration!
34 extern char backpackVersion
[];
36 static char version_domain
[20+1+6+1];
37 char pwrFolderDynamicName
[] = "TX Power (1000 Dynamic)";
38 char vtxFolderDynamicName
[] = "VTX Admin (OFF:C:1 Aux11 )";
39 static char modelMatchUnit
[] = " (ID: 00)";
40 static char tlmBandwidth
[] = " (xxxxxbps)";
41 static const char folderNameSeparator
[2] = {' ',':'};
42 static const char tlmRatios
[] = "Std;Off;1:128;1:64;1:32;1:16;1:8;1:4;1:2;Race";
43 static const char tlmRatiosMav
[] = ";;;;;;;;1:2;";
44 static const char switchmodeOpts4ch
[] = "Wide;Hybrid";
45 static const char switchmodeOpts4chMav
[] = ";Hybrid";
46 static const char switchmodeOpts8ch
[] = "8ch;16ch Rate/2;12ch Mixed";
47 static const char switchmodeOpts8chMav
[] = ";16ch Rate/2;";
48 static const char antennamodeOpts
[] = "Gemini;Ant 1;Ant 2;Switch";
49 static const char linkModeOpts
[] = "Normal;MAVLink";
50 static const char luastrDvrAux
[] = "Off;" STR_LUA_ALLAUX_UPDOWN
;
51 static const char luastrDvrDelay
[] = "0s;5s;15s;30s;45s;1min;2min";
52 static const char luastrHeadTrackingEnable
[] = "Off;On;" STR_LUA_ALLAUX_UPDOWN
;
53 static const char luastrHeadTrackingStart
[] = STR_LUA_ALLAUX
;
54 static const char luastrOffOn
[] = "Off;On";
55 static char luastrPacketRates
[] = STR_LUA_PACKETRATES
;
57 #define HAS_RADIO (GPIO_PIN_SCK != UNDEF_PIN)
59 static struct luaItem_selection luaAirRate
= {
60 {"Packet Rate", CRSF_TEXT_SELECTION
},
66 static struct luaItem_selection luaTlmRate
= {
67 {"Telem Ratio", CRSF_TEXT_SELECTION
},
73 //----------------------------POWER------------------
74 static struct luaItem_folder luaPowerFolder
= {
75 {"TX Power", CRSF_FOLDER
},pwrFolderDynamicName
78 static struct luaItem_selection luaPower
= {
79 {"Max Power", CRSF_TEXT_SELECTION
},
85 static struct luaItem_selection luaDynamicPower
= {
86 {"Dynamic", CRSF_TEXT_SELECTION
},
88 "Off;Dyn;AUX9;AUX10;AUX11;AUX12",
92 #if defined(GPIO_PIN_FAN_EN) || defined(GPIO_PIN_FAN_PWM)
93 static struct luaItem_selection luaFanThreshold
= {
94 {"Fan Thresh", CRSF_TEXT_SELECTION
},
96 "10mW;25mW;50mW;100mW;250mW;500mW;1000mW;2000mW;Never",
97 STR_EMPTYSPACE
// units embedded so it won't display "NevermW"
101 #if defined(Regulatory_Domain_EU_CE_2400)
102 static struct luaItem_string luaCELimit
= {
103 {"100mW CE LIMIT", CRSF_INFO
},
108 //----------------------------POWER------------------
110 static struct luaItem_selection luaSwitch
= {
111 {"Switch Mode", CRSF_TEXT_SELECTION
},
117 #if defined(GPIO_PIN_NSS_2)
118 static struct luaItem_selection luaAntenna
= {
119 {"Antenna Mode", CRSF_TEXT_SELECTION
},
126 static struct luaItem_selection luaLinkMode
= {
127 {"Link Mode", CRSF_TEXT_SELECTION
},
133 static struct luaItem_selection luaModelMatch
= {
134 {"Model Match", CRSF_TEXT_SELECTION
},
140 static struct luaItem_command luaBind
= {
141 {"Bind", CRSF_COMMAND
},
146 static struct luaItem_string luaInfo
= {
147 {"Bad/Good", (crsf_value_type_e
)(CRSF_INFO
| CRSF_FIELD_ELRS_HIDDEN
)},
151 static struct luaItem_string luaELRSversion
= {
152 {version_domain
, CRSF_INFO
},
156 //---------------------------- WiFi -----------------------------
157 static struct luaItem_folder luaWiFiFolder
= {
158 {"WiFi Connectivity", CRSF_FOLDER
}
161 #if defined(PLATFORM_ESP32) || defined(PLATFORM_ESP8266)
162 static struct luaItem_command luaWebUpdate
= {
163 {"Enable WiFi", CRSF_COMMAND
},
169 static struct luaItem_command luaRxWebUpdate
= {
170 {"Enable Rx WiFi", CRSF_COMMAND
},
175 static struct luaItem_command luaTxBackpackUpdate
= {
176 {"Enable Backpack WiFi", CRSF_COMMAND
},
181 static struct luaItem_command luaVRxBackpackUpdate
= {
182 {"Enable VRx WiFi", CRSF_COMMAND
},
186 //---------------------------- WiFi -----------------------------
188 #if defined(PLATFORM_ESP32)
189 static struct luaItem_command luaBLEJoystick
= {
190 {"BLE Joystick", CRSF_COMMAND
},
196 //----------------------------VTX ADMINISTRATOR------------------
197 static struct luaItem_folder luaVtxFolder
= {
198 {"VTX Administrator", CRSF_FOLDER
},vtxFolderDynamicName
201 static struct luaItem_selection luaVtxBand
= {
202 {"Band", CRSF_TEXT_SELECTION
},
208 static struct luaItem_int8 luaVtxChannel
= {
209 {"Channel", CRSF_UINT8
},
216 static struct luaItem_selection luaVtxPwr
= {
217 {"Pwr Lvl", CRSF_TEXT_SELECTION
},
223 static struct luaItem_selection luaVtxPit
= {
224 {"Pitmode", CRSF_TEXT_SELECTION
},
226 "Off;On;" STR_LUA_ALLAUX_UPDOWN
,
230 static struct luaItem_command luaVtxSend
= {
231 {"Send VTx", CRSF_COMMAND
},
235 //----------------------------VTX ADMINISTRATOR------------------
237 #if defined(TARGET_TX_FM30)
238 struct luaItem_selection luaBluetoothTelem
= {
239 {"BT Telemetry", CRSF_TEXT_SELECTION
},
246 //---------------------------- BACKPACK ------------------
247 static struct luaItem_folder luaBackpackFolder
= {
248 {"Backpack", CRSF_FOLDER
},
251 #if defined(GPIO_PIN_BACKPACK_EN)
252 static struct luaItem_selection luaBackpackEnable
= {
253 {"Backpack", CRSF_TEXT_SELECTION
},
259 static struct luaItem_selection luaDvrAux
= {
260 {"DVR Rec", CRSF_TEXT_SELECTION
},
265 static struct luaItem_selection luaDvrStartDelay
= {
266 {"DVR Srt Dly", CRSF_TEXT_SELECTION
},
271 static struct luaItem_selection luaDvrStopDelay
= {
272 {"DVR Stp Dly", CRSF_TEXT_SELECTION
},
277 static struct luaItem_selection luaHeadTrackingEnableChannel
= {
278 {"HT Enable", CRSF_TEXT_SELECTION
},
280 luastrHeadTrackingEnable
,
283 static struct luaItem_selection luaHeadTrackingStartChannel
= {
284 {"HT Start Channel", CRSF_TEXT_SELECTION
},
286 luastrHeadTrackingStart
,
289 static struct luaItem_selection luaBackpackTelemetry
= {
290 {"Telemetry", CRSF_TEXT_SELECTION
},
295 static struct luaItem_string luaBackpackVersion
= {
296 {"Version", CRSF_INFO
},
299 //---------------------------- BACKPACK ------------------
301 static char luaBadGoodString
[10];
304 extern TxConfig config
;
305 extern void VtxTriggerSend();
306 extern void ResetPower();
307 extern uint8_t adjustPacketRateForBaud(uint8_t rate
);
308 extern void SetSyncSpam();
309 extern bool RxWiFiReadyToSend
;
310 extern bool BackpackTelemReadyToSend
;
311 #if defined(USE_TX_BACKPACK)
312 extern bool TxBackpackWiFiReadyToSend
;
313 extern bool VRxBackpackWiFiReadyToSend
;
315 #if defined(PLATFORM_ESP32) || defined(PLATFORM_ESP8266)
316 extern unsigned long rebootTime
;
317 extern void setWifiUpdateMode();
320 static void luadevUpdateModelID() {
321 itoa(CRSFHandset::getModelID(), modelMatchUnit
+6, 10);
322 strcat(modelMatchUnit
, ")");
325 static void luadevUpdateTlmBandwidth()
327 expresslrs_tlm_ratio_e eRatio
= (expresslrs_tlm_ratio_e
)config
.GetTlm();
328 // TLM_RATIO_STD / TLM_RATIO_DISARMED
329 if (eRatio
== TLM_RATIO_STD
|| eRatio
== TLM_RATIO_DISARMED
)
331 // For Standard ratio, display the ratio instead of bps
332 strcpy(tlmBandwidth
, " (1:");
333 uint8_t ratioDiv
= TLMratioEnumToValue(ExpressLRS_currAirRate_Modparams
->TLMinterval
);
334 itoa(ratioDiv
, &tlmBandwidth
[4], 10);
335 strcat(tlmBandwidth
, ")");
339 else if (eRatio
== TLM_RATIO_NO_TLM
)
341 tlmBandwidth
[0] = '\0';
347 tlmBandwidth
[0] = ' ';
349 uint16_t hz
= 1000000 / ExpressLRS_currAirRate_Modparams
->interval
;
350 uint8_t ratiodiv
= TLMratioEnumToValue(eRatio
);
351 uint8_t burst
= TLMBurstMaxForRateRatio(hz
, ratiodiv
);
352 uint8_t bytesPerCall
= OtaIsFullRes
? ELRS8_TELEMETRY_BYTES_PER_CALL
: ELRS4_TELEMETRY_BYTES_PER_CALL
;
353 uint32_t bandwidthValue
= bytesPerCall
* 8U * burst
* hz
/ ratiodiv
/ (burst
+ 1);
356 // Due to fullres also packing telemetry into the LinkStats packet, there is at least
357 // N bytes more data for every rate except 100Hz 1:128, and 2*N bytes more for many
358 // rates. The calculation is a more complex though, so just approximate some of the
360 bandwidthValue
+= 8U * (ELRS8_TELEMETRY_BYTES_PER_CALL
- sizeof(OTA_LinkStats_s
));
363 itoa(bandwidthValue
, &tlmBandwidth
[2], 10);
364 strcat(tlmBandwidth
, "bps)");
368 static void luadevUpdateBackpackOpts()
370 if (config
.GetBackpackDisable())
372 // If backpack is disabled, set all the Backpack select options to "Disabled"
373 LUA_FIELD_HIDE(luaDvrAux
);
374 LUA_FIELD_HIDE(luaDvrStartDelay
);
375 LUA_FIELD_HIDE(luaDvrStopDelay
);
376 LUA_FIELD_HIDE(luaHeadTrackingEnableChannel
);
377 LUA_FIELD_HIDE(luaHeadTrackingStartChannel
);
378 LUA_FIELD_HIDE(luaBackpackTelemetry
);
379 LUA_FIELD_HIDE(luaBackpackVersion
);
383 LUA_FIELD_SHOW(luaDvrAux
);
384 LUA_FIELD_SHOW(luaDvrStartDelay
);
385 LUA_FIELD_SHOW(luaDvrStopDelay
);
386 LUA_FIELD_SHOW(luaHeadTrackingEnableChannel
);
387 LUA_FIELD_SHOW(luaHeadTrackingStartChannel
);
388 LUA_FIELD_SHOW(luaBackpackTelemetry
);
389 LUA_FIELD_SHOW(luaBackpackVersion
);
393 #if defined(PLATFORM_ESP32) || defined(PLATFORM_ESP8266)
394 static void setBleJoystickMode()
396 connectionState
= bleJoystick
;
399 static void luahandWifiBle(struct luaPropertiesCommon
*item
, uint8_t arg
)
401 struct luaItem_command
*cmd
= (struct luaItem_command
*)item
;
402 void (*setTargetState
)();
403 connectionState_e targetState
;
404 const char *textConfirm
;
405 const char *textRunning
;
406 if ((void *)item
== (void *)&luaWebUpdate
)
408 setTargetState
= &setWifiUpdateMode
;
409 textConfirm
= "Enter WiFi Update?";
410 textRunning
= "WiFi Running...";
411 targetState
= wifiUpdate
;
415 setTargetState
= &setBleJoystickMode
;
416 textConfirm
= "Start BLE Joystick?";
417 textRunning
= "Joystick Running...";
418 targetState
= bleJoystick
;
421 switch ((luaCmdStep_e
)arg
)
424 if (connectionState
== connected
)
426 sendLuaCommandResponse(cmd
, lcsAskConfirm
, textConfirm
);
429 // fallthrough (clicking while not connected goes right to exectute)
432 sendLuaCommandResponse(cmd
, lcsExecuting
, textRunning
);
437 sendLuaCommandResponse(cmd
, lcsIdle
, STR_EMPTYSPACE
);
438 if (connectionState
== targetState
)
440 rebootTime
= millis() + 400;
444 default: // LUACMDSTEP_NONE on load, LUACMDSTEP_EXECUTING (our lua) or LUACMDSTEP_QUERY (Crossfire Config)
445 sendLuaCommandResponse(cmd
, cmd
->step
, cmd
->info
);
451 static void luahandSimpleSendCmd(struct luaPropertiesCommon
*item
, uint8_t arg
)
453 const char *msg
= "Sending...";
454 static uint32_t lastLcsPoll
;
457 lastLcsPoll
= millis();
458 if ((void *)item
== (void *)&luaBind
)
461 EnterBindingModeSafely();
463 else if ((void *)item
== (void *)&luaVtxSend
)
467 else if ((void *)item
== (void *)&luaRxWebUpdate
)
469 RxWiFiReadyToSend
= true;
471 #if defined(USE_TX_BACKPACK)
472 else if ((void *)item
== (void *)&luaTxBackpackUpdate
&& OPT_USE_TX_BACKPACK
)
474 TxBackpackWiFiReadyToSend
= true;
476 else if ((void *)item
== (void *)&luaVRxBackpackUpdate
&& OPT_USE_TX_BACKPACK
)
478 VRxBackpackWiFiReadyToSend
= true;
481 sendLuaCommandResponse((struct luaItem_command
*)item
, lcsExecuting
, msg
);
483 else if(arg
== lcsCancel
|| ((millis() - lastLcsPoll
)> 2000))
485 sendLuaCommandResponse((struct luaItem_command
*)item
, lcsIdle
, STR_EMPTYSPACE
);
489 static void updateFolderName_TxPower()
491 uint8_t txPwrDyn
= config
.GetDynamicPower() ? config
.GetBoostChannel() + 1 : 0;
492 uint8_t pwrFolderLabelOffset
= 10; // start writing after "TX Power ("
495 pwrFolderLabelOffset
+= findLuaSelectionLabel(&luaPower
, &pwrFolderDynamicName
[pwrFolderLabelOffset
], config
.GetPower() - MinPower
);
500 pwrFolderDynamicName
[pwrFolderLabelOffset
++] = folderNameSeparator
[0];
501 pwrFolderLabelOffset
+= findLuaSelectionLabel(&luaDynamicPower
, &pwrFolderDynamicName
[pwrFolderLabelOffset
], txPwrDyn
);
504 pwrFolderDynamicName
[pwrFolderLabelOffset
++] = ')';
505 pwrFolderDynamicName
[pwrFolderLabelOffset
] = '\0';
508 static void updateFolderName_VtxAdmin()
510 uint8_t vtxBand
= config
.GetVtxBand();
513 luaVtxFolder
.dyn_name
= vtxFolderDynamicName
;
514 uint8_t vtxFolderLabelOffset
= 11; // start writing after "VTX Admin ("
517 vtxFolderLabelOffset
+= findLuaSelectionLabel(&luaVtxBand
, &vtxFolderDynamicName
[vtxFolderLabelOffset
], vtxBand
);
518 vtxFolderDynamicName
[vtxFolderLabelOffset
++] = folderNameSeparator
[1];
521 vtxFolderDynamicName
[vtxFolderLabelOffset
++] = '1' + config
.GetVtxChannel();
524 uint8_t vtxPwr
= config
.GetVtxPower();
525 //if power is no-change (-), don't show, also hide pitmode
528 vtxFolderDynamicName
[vtxFolderLabelOffset
++] = folderNameSeparator
[1];
529 vtxFolderLabelOffset
+= findLuaSelectionLabel(&luaVtxPwr
, &vtxFolderDynamicName
[vtxFolderLabelOffset
], vtxPwr
);
532 uint8_t vtxPit
= config
.GetVtxPitmode();
533 //if pitmode is off, don't show
534 //show pitmode AuxSwitch or show P if not OFF
539 vtxFolderDynamicName
[vtxFolderLabelOffset
++] = folderNameSeparator
[1];
540 vtxFolderLabelOffset
+= findLuaSelectionLabel(&luaVtxPit
, &vtxFolderDynamicName
[vtxFolderLabelOffset
], vtxPit
);
544 vtxFolderDynamicName
[vtxFolderLabelOffset
++] = folderNameSeparator
[1];
545 vtxFolderDynamicName
[vtxFolderLabelOffset
++] = 'P';
549 vtxFolderDynamicName
[vtxFolderLabelOffset
++] = ')';
550 vtxFolderDynamicName
[vtxFolderLabelOffset
] = '\0';
554 //don't show vtx settings if band is OFF
555 luaVtxFolder
.dyn_name
= NULL
;
560 * @brief: Update the luaBadGoodString with the current bad/good count
561 * This item is hidden on our Lua and only displayed in other systems that don't poll our status
562 * Called from luaRegisterDevicePingCallback
564 static void luadevUpdateBadGood()
566 itoa(CRSFHandset::BadPktsCountResult
, luaBadGoodString
, 10);
567 strcat(luaBadGoodString
, "/");
568 itoa(CRSFHandset::GoodPktsCountResult
, luaBadGoodString
+ strlen(luaBadGoodString
), 10);
572 * @brief: Update the dynamic strings used for folder names and labels
574 void luadevUpdateFolderNames()
576 updateFolderName_TxPower();
577 updateFolderName_VtxAdmin();
579 // These aren't folder names, just string labels slapped in the units field generally
580 luadevUpdateTlmBandwidth();
581 luadevUpdateBackpackOpts();
584 static void recalculatePacketRateOptions(int minInterval
)
586 const char *allRates
= STR_LUA_PACKETRATES
;
587 const char *pos
= allRates
;
588 luastrPacketRates
[0] = 0;
589 for (int i
=0 ; i
< RATE_MAX
; i
++)
592 rate
= RATE_MAX
- 1 - rate
;
593 bool rateAllowed
= (get_elrs_airRateConfig(rate
)->interval
* get_elrs_airRateConfig(rate
)->numOfSends
) >= minInterval
;
595 // Skip unsupported modes for hardware with only a single LR1121 or with a single RF path
596 rateAllowed
&= isSupportedRFRate(rate
);
598 const char *semi
= strchrnul(pos
, ';');
601 strncat(luastrPacketRates
, pos
, semi
- pos
);
606 strcat(luastrPacketRates
, ";");
611 // trim off trailing semicolons (assumes luastrPacketRates has at least 1 non-semicolon)
612 for (auto lastPos
= strlen(luastrPacketRates
)-1; luastrPacketRates
[lastPos
] == ';'; lastPos
--)
614 luastrPacketRates
[lastPos
] = '\0';
618 uint8_t adjustSwitchModeForAirRate(OtaSwitchMode_e eSwitchMode
, uint8_t packetSize
)
620 // Only the fullres modes have 3 switch modes, so reset the switch mode if outside the
621 // range for 4ch mode
622 if (packetSize
== OTA4_PACKET_SIZE
)
624 if (eSwitchMode
> smHybridOr16ch
)
631 static void registerLuaParameters()
634 registerLUAParameter(&luaAirRate
, [](struct luaPropertiesCommon
*item
, uint8_t arg
) {
637 uint8_t selectedRate
= RATE_MAX
- 1 - arg
;
638 uint8_t actualRate
= adjustPacketRateForBaud(selectedRate
);
639 uint8_t newSwitchMode
= adjustSwitchModeForAirRate(
640 (OtaSwitchMode_e
)config
.GetSwitchMode(), get_elrs_airRateConfig(actualRate
)->PayloadLength
);
641 // If the switch mode is going to change, block the change while connected
642 bool isDisconnected
= connectionState
== disconnected
;
643 // Don't allow the switch mode to change if the TX is in mavlink mode
644 // Wide switchmode is not compatible with mavlink, and the switchmode is
645 // auto configuredwhen entering mavlink mode
646 bool isMavlinkMode
= config
.GetLinkMode() == TX_MAVLINK_MODE
;
647 if (newSwitchMode
== OtaSwitchModeCurrent
|| (isDisconnected
&& !isMavlinkMode
))
649 config
.SetRate(actualRate
);
650 config
.SetSwitchMode(newSwitchMode
);
651 if (actualRate
!= selectedRate
)
653 setLuaWarningFlag(LUA_FLAG_ERROR_BAUDRATE
, true);
657 setLuaWarningFlag(LUA_FLAG_ERROR_CONNECTED
, true);
660 registerLUAParameter(&luaTlmRate
, [](struct luaPropertiesCommon
*item
, uint8_t arg
) {
661 expresslrs_tlm_ratio_e eRatio
= (expresslrs_tlm_ratio_e
)arg
;
662 if (eRatio
<= TLM_RATIO_DISARMED
)
664 bool isMavlinkMode
= config
.GetLinkMode() == TX_MAVLINK_MODE
;
665 // Don't allow TLM ratio changes if using AIRPORT or Mavlink
666 if (!firmwareOptions
.is_airport
&& !isMavlinkMode
)
668 config
.SetTlm(eRatio
);
672 #if defined(TARGET_TX_FM30)
673 registerLUAParameter(&luaBluetoothTelem
, [](struct luaPropertiesCommon
*item
, uint8_t arg
) {
674 digitalWrite(GPIO_PIN_BLUETOOTH_EN
, !arg
);
675 devicesTriggerEvent();
678 if (!firmwareOptions
.is_airport
)
680 registerLUAParameter(&luaSwitch
, [](struct luaPropertiesCommon
*item
, uint8_t arg
) {
681 // Only allow changing switch mode when disconnected since we need to guarantee
682 // the pack and unpack functions are matched
683 bool isDisconnected
= connectionState
== disconnected
;
684 // Don't allow the switch mode to change if the TX is in mavlink mode
685 // Wide switchmode is not compatible with mavlink, and the switchmode is
686 // auto configuredwhen entering mavlink mode
687 bool isMavlinkMode
= config
.GetLinkMode() == TX_MAVLINK_MODE
;
688 if (isDisconnected
&& !isMavlinkMode
)
690 config
.SetSwitchMode(arg
);
691 OtaUpdateSerializers((OtaSwitchMode_e
)arg
, ExpressLRS_currAirRate_Modparams
->PayloadLength
);
693 else if (!isMavlinkMode
) // No need to display warning as no switch change can be made while in Mavlink mode.
695 setLuaWarningFlag(LUA_FLAG_ERROR_CONNECTED
, true);
701 registerLUAParameter(&luaAntenna
, [](struct luaPropertiesCommon
*item
, uint8_t arg
) {
702 config
.SetAntennaMode(arg
);
705 registerLUAParameter(&luaLinkMode
, [](struct luaPropertiesCommon
*item
, uint8_t arg
) {
706 // Only allow changing when disconnected since we need to guarantee
707 // the switch pack and unpack functions are matched on the tx and rx.
708 bool isDisconnected
= connectionState
== disconnected
;
711 config
.SetLinkMode(arg
);
715 setLuaWarningFlag(LUA_FLAG_ERROR_CONNECTED
, true);
718 if (!firmwareOptions
.is_airport
)
720 registerLUAParameter(&luaModelMatch
, [](struct luaPropertiesCommon
*item
, uint8_t arg
) {
721 bool newModelMatch
= arg
;
722 config
.SetModelMatch(newModelMatch
);
723 if (connectionState
== connected
)
728 msp
.function
= MSP_SET_RX_CONFIG
;
729 msp
.addByte(MSP_ELRS_MODEL_ID
);
730 msp
.addByte(newModelMatch
? CRSFHandset::getModelID() : 0xff);
731 CRSF::AddMspMessage(&msp
, CRSF_ADDRESS_CRSF_RECEIVER
);
733 luadevUpdateModelID();
738 registerLUAParameter(&luaPowerFolder
);
739 luadevGeneratePowerOpts(&luaPower
);
740 registerLUAParameter(&luaPower
, [](struct luaPropertiesCommon
*item
, uint8_t arg
) {
741 config
.SetPower((PowerLevels_e
)constrain(arg
+ POWERMGNT::getMinPower(), POWERMGNT::getMinPower(), POWERMGNT::getMaxPower()));
742 if (!config
.IsModified())
746 }, luaPowerFolder
.common
.id
);
747 registerLUAParameter(&luaDynamicPower
, [](struct luaPropertiesCommon
*item
, uint8_t arg
) {
748 config
.SetDynamicPower(arg
> 0);
749 config
.SetBoostChannel((arg
- 1) > 0 ? arg
- 1 : 0);
750 }, luaPowerFolder
.common
.id
);
752 if (GPIO_PIN_FAN_EN
!= UNDEF_PIN
|| GPIO_PIN_FAN_PWM
!= UNDEF_PIN
) {
753 registerLUAParameter(&luaFanThreshold
, [](struct luaPropertiesCommon
*item
, uint8_t arg
){
754 config
.SetPowerFanThreshold(arg
);
755 }, luaPowerFolder
.common
.id
);
757 #if defined(Regulatory_Domain_EU_CE_2400)
759 registerLUAParameter(&luaCELimit
, NULL
, luaPowerFolder
.common
.id
);
762 if ((HAS_RADIO
|| OPT_USE_TX_BACKPACK
) && !firmwareOptions
.is_airport
) {
764 registerLUAParameter(&luaVtxFolder
);
765 registerLUAParameter(&luaVtxBand
, [](struct luaPropertiesCommon
*item
, uint8_t arg
) {
766 config
.SetVtxBand(arg
);
767 }, luaVtxFolder
.common
.id
);
768 registerLUAParameter(&luaVtxChannel
, [](struct luaPropertiesCommon
*item
, uint8_t arg
) {
769 config
.SetVtxChannel(arg
- 1);
770 }, luaVtxFolder
.common
.id
);
771 registerLUAParameter(&luaVtxPwr
, [](struct luaPropertiesCommon
*item
, uint8_t arg
) {
772 config
.SetVtxPower(arg
);
773 }, luaVtxFolder
.common
.id
);
774 registerLUAParameter(&luaVtxPit
, [](struct luaPropertiesCommon
*item
, uint8_t arg
) {
775 config
.SetVtxPitmode(arg
);
776 }, luaVtxFolder
.common
.id
);
777 registerLUAParameter(&luaVtxSend
, &luahandSimpleSendCmd
, luaVtxFolder
.common
.id
);
781 #if defined(PLATFORM_ESP32) || defined(PLATFORM_ESP8266)
782 registerLUAParameter(&luaWiFiFolder
);
783 registerLUAParameter(&luaWebUpdate
, &luahandWifiBle
, luaWiFiFolder
.common
.id
);
785 if (HAS_RADIO
|| OPT_USE_TX_BACKPACK
) {
786 registerLUAParameter(&luaWiFiFolder
);
790 registerLUAParameter(&luaRxWebUpdate
, &luahandSimpleSendCmd
, luaWiFiFolder
.common
.id
);
792 if (OPT_USE_TX_BACKPACK
) {
793 registerLUAParameter(&luaTxBackpackUpdate
, &luahandSimpleSendCmd
, luaWiFiFolder
.common
.id
);
794 registerLUAParameter(&luaVRxBackpackUpdate
, &luahandSimpleSendCmd
, luaWiFiFolder
.common
.id
);
796 registerLUAParameter(&luaBackpackFolder
);
797 #if defined(GPIO_PIN_BACKPACK_EN)
798 if (GPIO_PIN_BACKPACK_EN
!= UNDEF_PIN
)
800 registerLUAParameter(
801 &luaBackpackEnable
, [](luaPropertiesCommon
*item
, uint8_t arg
) {
802 // option is Off/On (enable) and config storage is On/Off (disable)
803 config
.SetBackpackDisable(arg
== 0);
804 }, luaBackpackFolder
.common
.id
);
807 registerLUAParameter(
808 &luaDvrAux
, [](luaPropertiesCommon
*item
, uint8_t arg
) {
809 if (config
.GetBackpackDisable() == false)
810 config
.SetDvrAux(arg
);
812 luaBackpackFolder
.common
.id
);
813 registerLUAParameter(
814 &luaDvrStartDelay
, [](luaPropertiesCommon
*item
, uint8_t arg
) {
815 if (config
.GetBackpackDisable() == false)
816 config
.SetDvrStartDelay(arg
);
818 luaBackpackFolder
.common
.id
);
819 registerLUAParameter(
820 &luaDvrStopDelay
, [](luaPropertiesCommon
*item
, uint8_t arg
) {
821 if (config
.GetBackpackDisable() == false)
822 config
.SetDvrStopDelay(arg
);
824 luaBackpackFolder
.common
.id
);
825 registerLUAParameter(
826 &luaHeadTrackingEnableChannel
, [](luaPropertiesCommon
*item
, uint8_t arg
) {
827 config
.SetPTREnableChannel(arg
);
829 luaBackpackFolder
.common
.id
);
830 registerLUAParameter(
831 &luaHeadTrackingStartChannel
, [](luaPropertiesCommon
*item
, uint8_t arg
) {
832 config
.SetPTRStartChannel(arg
);
834 luaBackpackFolder
.common
.id
);
835 registerLUAParameter(
836 &luaBackpackTelemetry
, [](luaPropertiesCommon
*item
, uint8_t arg
) {
837 config
.SetBackpackTlmMode(arg
);
838 BackpackTelemReadyToSend
= true;
839 }, luaBackpackFolder
.common
.id
);
841 registerLUAParameter(&luaBackpackVersion
, nullptr, luaBackpackFolder
.common
.id
);
845 #if defined(PLATFORM_ESP32)
846 registerLUAParameter(&luaBLEJoystick
, &luahandWifiBle
);
850 registerLUAParameter(&luaBind
, &luahandSimpleSendCmd
);
853 registerLUAParameter(&luaInfo
);
854 if (strlen(version
) < 21) {
855 strlcpy(version_domain
, version
, 21);
856 strlcat(version_domain
, " ", sizeof(version_domain
));
858 strlcpy(version_domain
, version
, 18);
859 strlcat(version_domain
, "... ", sizeof(version_domain
));
861 strlcat(version_domain
, FHSSconfig
->domain
, sizeof(version_domain
));
862 registerLUAParameter(&luaELRSversion
);
863 registerLUAParameter(NULL
);
868 if (connectionState
> FAILURE_STATES
)
870 return DURATION_NEVER
;
873 bool isMavlinkMode
= config
.GetLinkMode() == TX_MAVLINK_MODE
;
874 uint8_t currentRate
= adjustPacketRateForBaud(config
.GetRate());
875 recalculatePacketRateOptions(handset
->getMinPacketInterval());
876 setLuaTextSelectionValue(&luaAirRate
, RATE_MAX
- 1 - currentRate
);
878 setLuaTextSelectionValue(&luaTlmRate
, config
.GetTlm());
879 luaTlmRate
.options
= isMavlinkMode
? tlmRatiosMav
: tlmRatios
;
881 setLuaTextSelectionValue(&luaSwitch
, config
.GetSwitchMode());
884 luaSwitch
.options
= OtaIsFullRes
? switchmodeOpts8chMav
: switchmodeOpts4chMav
;
888 luaSwitch
.options
= OtaIsFullRes
? switchmodeOpts8ch
: switchmodeOpts4ch
;
893 setLuaTextSelectionValue(&luaAntenna
, config
.GetAntennaMode());
895 setLuaTextSelectionValue(&luaLinkMode
, config
.GetLinkMode());
896 luadevUpdateModelID();
897 setLuaTextSelectionValue(&luaModelMatch
, (uint8_t)config
.GetModelMatch());
898 setLuaTextSelectionValue(&luaPower
, config
.GetPower() - MinPower
);
899 if (GPIO_PIN_FAN_EN
!= UNDEF_PIN
|| GPIO_PIN_FAN_PWM
!= UNDEF_PIN
)
901 setLuaTextSelectionValue(&luaFanThreshold
, config
.GetPowerFanThreshold());
904 uint8_t dynamic
= config
.GetDynamicPower() ? config
.GetBoostChannel() + 1 : 0;
905 setLuaTextSelectionValue(&luaDynamicPower
, dynamic
);
907 setLuaTextSelectionValue(&luaVtxBand
, config
.GetVtxBand());
908 setLuaUint8Value(&luaVtxChannel
, config
.GetVtxChannel() + 1);
909 setLuaTextSelectionValue(&luaVtxPwr
, config
.GetVtxPower());
910 setLuaTextSelectionValue(&luaVtxPit
, config
.GetVtxPitmode());
911 if (OPT_USE_TX_BACKPACK
)
913 #if defined(GPIO_PIN_BACKPACK_EN)
914 setLuaTextSelectionValue(&luaBackpackEnable
, config
.GetBackpackDisable() ? 0 : 1);
916 setLuaTextSelectionValue(&luaDvrAux
, config
.GetBackpackDisable() ? 0 : config
.GetDvrAux());
917 setLuaTextSelectionValue(&luaDvrStartDelay
, config
.GetBackpackDisable() ? 0 : config
.GetDvrStartDelay());
918 setLuaTextSelectionValue(&luaDvrStopDelay
, config
.GetBackpackDisable() ? 0 : config
.GetDvrStopDelay());
919 setLuaTextSelectionValue(&luaHeadTrackingEnableChannel
, config
.GetBackpackDisable() ? 0 : config
.GetPTREnableChannel());
920 setLuaTextSelectionValue(&luaHeadTrackingStartChannel
, config
.GetBackpackDisable() ? 0 : config
.GetPTRStartChannel());
921 setLuaTextSelectionValue(&luaBackpackTelemetry
, config
.GetBackpackDisable() ? 0 : config
.GetBackpackTlmMode());
922 setLuaStringValue(&luaBackpackVersion
, backpackVersion
);
924 #if defined(TARGET_TX_FM30)
925 setLuaTextSelectionValue(&luaBluetoothTelem
, !digitalRead(GPIO_PIN_BLUETOOTH_EN
));
927 luadevUpdateFolderNames();
928 return DURATION_IMMEDIATELY
;
933 if (luaHandleUpdateParameter())
937 return DURATION_IMMEDIATELY
;
942 if (connectionState
> FAILURE_STATES
)
944 return DURATION_NEVER
;
946 handset
->registerParameterUpdateCallback(luaParamUpdateReq
);
947 registerLuaParameters();
949 setLuaStringValue(&luaInfo
, luaBadGoodString
);
950 luaRegisterDevicePingCallback(&luadevUpdateBadGood
);
953 return DURATION_IMMEDIATELY
;
956 device_t LUA_device
= {