change-to-sending-expresslrs_RFrates_e-in-sync-packet
[ExpressLRS.git] / src / lib / LUA / tx_devLUA.cpp
blobe38f318f26c257743b956452f7410dd55cef4ef0
1 #ifdef TARGET_TX
3 #include "rxtx_devLua.h"
4 #include "CRSF.h"
5 #include "CRSFHandset.h"
6 #include "OTA.h"
7 #include "FHSS.h"
8 #include "helpers.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 "X100F;X150;" \
24 "50 2.4G;100F 2.4G;150 2.4G;250 2.4G;333F 2.4G;500 2.4G;DK250 2.4G;DK500 2.4G;K1000 2.4G;" \
25 "D50 Low;25 Low;50 Low;100 Low;100F Low;200 Low;200F Low;250 Low;K1000F Low"
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)"
30 #else
31 #error Invalid radio configuration!
32 #endif
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},
61 0, // value
62 luastrPacketRates,
63 STR_EMPTYSPACE
66 static struct luaItem_selection luaTlmRate = {
67 {"Telem Ratio", CRSF_TEXT_SELECTION},
68 0, // value
69 tlmRatios,
70 tlmBandwidth
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},
80 0, // value
81 strPowerLevels,
82 "mW"
85 static struct luaItem_selection luaDynamicPower = {
86 {"Dynamic", CRSF_TEXT_SELECTION},
87 0, // value
88 "Off;Dyn;AUX9;AUX10;AUX11;AUX12",
89 STR_EMPTYSPACE
92 #if defined(GPIO_PIN_FAN_EN) || defined(GPIO_PIN_FAN_PWM)
93 static struct luaItem_selection luaFanThreshold = {
94 {"Fan Thresh", CRSF_TEXT_SELECTION},
95 0, // value
96 "10mW;25mW;50mW;100mW;250mW;500mW;1000mW;2000mW;Never",
97 STR_EMPTYSPACE // units embedded so it won't display "NevermW"
99 #endif
101 #if defined(Regulatory_Domain_EU_CE_2400)
102 static struct luaItem_string luaCELimit = {
103 {"100mW CE LIMIT", CRSF_INFO},
104 STR_EMPTYSPACE
106 #endif
108 //----------------------------POWER------------------
110 static struct luaItem_selection luaSwitch = {
111 {"Switch Mode", CRSF_TEXT_SELECTION},
112 0, // value
113 switchmodeOpts4ch,
114 STR_EMPTYSPACE
117 #if defined(GPIO_PIN_NSS_2)
118 static struct luaItem_selection luaAntenna = {
119 {"Antenna Mode", CRSF_TEXT_SELECTION},
120 0, // value
121 antennamodeOpts,
122 STR_EMPTYSPACE
124 #endif
126 static struct luaItem_selection luaLinkMode = {
127 {"Link Mode", CRSF_TEXT_SELECTION},
128 0, // value
129 linkModeOpts,
130 STR_EMPTYSPACE
133 static struct luaItem_selection luaModelMatch = {
134 {"Model Match", CRSF_TEXT_SELECTION},
135 0, // value
136 luastrOffOn,
137 modelMatchUnit
140 static struct luaItem_command luaBind = {
141 {"Bind", CRSF_COMMAND},
142 lcsIdle, // step
143 STR_EMPTYSPACE
146 static struct luaItem_string luaInfo = {
147 {"Bad/Good", (crsf_value_type_e)(CRSF_INFO | CRSF_FIELD_ELRS_HIDDEN)},
148 STR_EMPTYSPACE
151 static struct luaItem_string luaELRSversion = {
152 {version_domain, CRSF_INFO},
153 commit
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},
164 lcsIdle, // step
165 STR_EMPTYSPACE
167 #endif
169 static struct luaItem_command luaRxWebUpdate = {
170 {"Enable Rx WiFi", CRSF_COMMAND},
171 lcsIdle, // step
172 STR_EMPTYSPACE
175 static struct luaItem_command luaTxBackpackUpdate = {
176 {"Enable Backpack WiFi", CRSF_COMMAND},
177 lcsIdle, // step
178 STR_EMPTYSPACE
181 static struct luaItem_command luaVRxBackpackUpdate = {
182 {"Enable VRx WiFi", CRSF_COMMAND},
183 lcsIdle, // step
184 STR_EMPTYSPACE
186 //---------------------------- WiFi -----------------------------
188 #if defined(PLATFORM_ESP32)
189 static struct luaItem_command luaBLEJoystick = {
190 {"BLE Joystick", CRSF_COMMAND},
191 lcsIdle, // step
192 STR_EMPTYSPACE
194 #endif
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},
203 0, // value
204 "Off;A;B;E;F;R;L",
205 STR_EMPTYSPACE
208 static struct luaItem_int8 luaVtxChannel = {
209 {"Channel", CRSF_UINT8},
210 0, // value
211 1, // min
212 8, // max
213 STR_EMPTYSPACE
216 static struct luaItem_selection luaVtxPwr = {
217 {"Pwr Lvl", CRSF_TEXT_SELECTION},
218 0, // value
219 "-;1;2;3;4;5;6;7;8",
220 STR_EMPTYSPACE
223 static struct luaItem_selection luaVtxPit = {
224 {"Pitmode", CRSF_TEXT_SELECTION},
225 0, // value
226 "Off;On;" STR_LUA_ALLAUX_UPDOWN,
227 STR_EMPTYSPACE
230 static struct luaItem_command luaVtxSend = {
231 {"Send VTx", CRSF_COMMAND},
232 lcsIdle, // step
233 STR_EMPTYSPACE
235 //----------------------------VTX ADMINISTRATOR------------------
237 #if defined(TARGET_TX_FM30)
238 struct luaItem_selection luaBluetoothTelem = {
239 {"BT Telemetry", CRSF_TEXT_SELECTION},
240 0, // value
241 luastrOffOn,
242 STR_EMPTYSPACE
244 #endif
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},
254 0, // value
255 luastrOffOn,
256 STR_EMPTYSPACE};
257 #endif
259 static struct luaItem_selection luaDvrAux = {
260 {"DVR Rec", CRSF_TEXT_SELECTION},
261 0, // value
262 luastrDvrAux,
263 STR_EMPTYSPACE};
265 static struct luaItem_selection luaDvrStartDelay = {
266 {"DVR Srt Dly", CRSF_TEXT_SELECTION},
267 0, // value
268 luastrDvrDelay,
269 STR_EMPTYSPACE};
271 static struct luaItem_selection luaDvrStopDelay = {
272 {"DVR Stp Dly", CRSF_TEXT_SELECTION},
273 0, // value
274 luastrDvrDelay,
275 STR_EMPTYSPACE};
277 static struct luaItem_selection luaHeadTrackingEnableChannel = {
278 {"HT Enable", CRSF_TEXT_SELECTION},
279 0, // value
280 luastrHeadTrackingEnable,
281 STR_EMPTYSPACE};
283 static struct luaItem_selection luaHeadTrackingStartChannel = {
284 {"HT Start Channel", CRSF_TEXT_SELECTION},
285 0, // value
286 luastrHeadTrackingStart,
287 STR_EMPTYSPACE};
289 static struct luaItem_selection luaBackpackTelemetry = {
290 {"Telemetry", CRSF_TEXT_SELECTION},
291 0, // value
292 luastrOffOn,
293 STR_EMPTYSPACE};
295 static struct luaItem_string luaBackpackVersion = {
296 {"Version", CRSF_INFO},
297 backpackVersion};
299 //---------------------------- BACKPACK ------------------
301 static char luaBadGoodString[10];
302 static int event();
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 #if defined(USE_TX_BACKPACK)
311 extern bool TxBackpackWiFiReadyToSend;
312 extern bool VRxBackpackWiFiReadyToSend;
313 #endif
314 #if defined(PLATFORM_ESP32) || defined(PLATFORM_ESP8266)
315 extern unsigned long rebootTime;
316 extern void setWifiUpdateMode();
317 #endif
319 static void luadevUpdateModelID() {
320 itoa(CRSFHandset::getModelID(), modelMatchUnit+6, 10);
321 strcat(modelMatchUnit, ")");
324 static void luadevUpdateTlmBandwidth()
326 expresslrs_tlm_ratio_e eRatio = (expresslrs_tlm_ratio_e)config.GetTlm();
327 // TLM_RATIO_STD / TLM_RATIO_DISARMED
328 if (eRatio == TLM_RATIO_STD || eRatio == TLM_RATIO_DISARMED)
330 // For Standard ratio, display the ratio instead of bps
331 strcpy(tlmBandwidth, " (1:");
332 uint8_t ratioDiv = TLMratioEnumToValue(ExpressLRS_currAirRate_Modparams->TLMinterval);
333 itoa(ratioDiv, &tlmBandwidth[4], 10);
334 strcat(tlmBandwidth, ")");
337 // TLM_RATIO_NO_TLM
338 else if (eRatio == TLM_RATIO_NO_TLM)
340 tlmBandwidth[0] = '\0';
343 // All normal ratios
344 else
346 tlmBandwidth[0] = ' ';
348 uint16_t hz = 1000000 / ExpressLRS_currAirRate_Modparams->interval;
349 uint8_t ratiodiv = TLMratioEnumToValue(eRatio);
350 uint8_t burst = TLMBurstMaxForRateRatio(hz, ratiodiv);
351 uint8_t bytesPerCall = OtaIsFullRes ? ELRS8_TELEMETRY_BYTES_PER_CALL : ELRS4_TELEMETRY_BYTES_PER_CALL;
352 uint32_t bandwidthValue = bytesPerCall * 8U * burst * hz / ratiodiv / (burst + 1);
353 if (OtaIsFullRes)
355 // Due to fullres also packing telemetry into the LinkStats packet, there is at least
356 // N bytes more data for every rate except 100Hz 1:128, and 2*N bytes more for many
357 // rates. The calculation is a more complex though, so just approximate some of the
358 // extra bandwidth
359 bandwidthValue += 8U * (ELRS8_TELEMETRY_BYTES_PER_CALL - sizeof(OTA_LinkStats_s));
362 itoa(bandwidthValue, &tlmBandwidth[2], 10);
363 strcat(tlmBandwidth, "bps)");
367 static void luadevUpdateBackpackOpts()
369 if (config.GetBackpackDisable())
371 // If backpack is disabled, set all the Backpack select options to "Disabled"
372 LUA_FIELD_HIDE(luaDvrAux);
373 LUA_FIELD_HIDE(luaDvrStartDelay);
374 LUA_FIELD_HIDE(luaDvrStopDelay);
375 LUA_FIELD_HIDE(luaHeadTrackingEnableChannel);
376 LUA_FIELD_HIDE(luaHeadTrackingStartChannel);
377 LUA_FIELD_HIDE(luaBackpackTelemetry);
378 LUA_FIELD_HIDE(luaBackpackVersion);
380 else
382 LUA_FIELD_SHOW(luaDvrAux);
383 LUA_FIELD_SHOW(luaDvrStartDelay);
384 LUA_FIELD_SHOW(luaDvrStopDelay);
385 LUA_FIELD_SHOW(luaHeadTrackingEnableChannel);
386 LUA_FIELD_SHOW(luaHeadTrackingStartChannel);
387 LUA_FIELD_SHOW(luaBackpackTelemetry);
388 LUA_FIELD_SHOW(luaBackpackVersion);
392 #if defined(PLATFORM_ESP32) || defined(PLATFORM_ESP8266)
393 static void setBleJoystickMode()
395 connectionState = bleJoystick;
398 static void luahandWifiBle(struct luaPropertiesCommon *item, uint8_t arg)
400 struct luaItem_command *cmd = (struct luaItem_command *)item;
401 void (*setTargetState)();
402 connectionState_e targetState;
403 const char *textConfirm;
404 const char *textRunning;
405 if ((void *)item == (void *)&luaWebUpdate)
407 setTargetState = &setWifiUpdateMode;
408 textConfirm = "Enter WiFi Update?";
409 textRunning = "WiFi Running...";
410 targetState = wifiUpdate;
412 else
414 setTargetState = &setBleJoystickMode;
415 textConfirm = "Start BLE Joystick?";
416 textRunning = "Joystick Running...";
417 targetState = bleJoystick;
420 switch ((luaCmdStep_e)arg)
422 case lcsClick:
423 if (connectionState == connected)
425 sendLuaCommandResponse(cmd, lcsAskConfirm, textConfirm);
426 return;
428 // fallthrough (clicking while not connected goes right to exectute)
430 case lcsConfirmed:
431 sendLuaCommandResponse(cmd, lcsExecuting, textRunning);
432 setTargetState();
433 break;
435 case lcsCancel:
436 sendLuaCommandResponse(cmd, lcsIdle, STR_EMPTYSPACE);
437 if (connectionState == targetState)
439 rebootTime = millis() + 400;
441 break;
443 default: // LUACMDSTEP_NONE on load, LUACMDSTEP_EXECUTING (our lua) or LUACMDSTEP_QUERY (Crossfire Config)
444 sendLuaCommandResponse(cmd, cmd->step, cmd->info);
445 break;
448 #endif
450 static void luahandSimpleSendCmd(struct luaPropertiesCommon *item, uint8_t arg)
452 const char *msg = "Sending...";
453 static uint32_t lastLcsPoll;
454 if (arg < lcsCancel)
456 lastLcsPoll = millis();
457 if ((void *)item == (void *)&luaBind)
459 msg = "Binding...";
460 EnterBindingModeSafely();
462 else if ((void *)item == (void *)&luaVtxSend)
464 VtxTriggerSend();
466 else if ((void *)item == (void *)&luaRxWebUpdate)
468 RxWiFiReadyToSend = true;
470 #if defined(USE_TX_BACKPACK)
471 else if ((void *)item == (void *)&luaTxBackpackUpdate && OPT_USE_TX_BACKPACK)
473 TxBackpackWiFiReadyToSend = true;
475 else if ((void *)item == (void *)&luaVRxBackpackUpdate && OPT_USE_TX_BACKPACK)
477 VRxBackpackWiFiReadyToSend = true;
479 #endif
480 sendLuaCommandResponse((struct luaItem_command *)item, lcsExecuting, msg);
481 } /* if doExecute */
482 else if(arg == lcsCancel || ((millis() - lastLcsPoll)> 2000))
484 sendLuaCommandResponse((struct luaItem_command *)item, lcsIdle, STR_EMPTYSPACE);
488 static void updateFolderName_TxPower()
490 uint8_t txPwrDyn = config.GetDynamicPower() ? config.GetBoostChannel() + 1 : 0;
491 uint8_t pwrFolderLabelOffset = 10; // start writing after "TX Power ("
493 // Power Level
494 pwrFolderLabelOffset += findLuaSelectionLabel(&luaPower, &pwrFolderDynamicName[pwrFolderLabelOffset], config.GetPower() - MinPower);
496 // Dynamic Power
497 if (txPwrDyn)
499 pwrFolderDynamicName[pwrFolderLabelOffset++] = folderNameSeparator[0];
500 pwrFolderLabelOffset += findLuaSelectionLabel(&luaDynamicPower, &pwrFolderDynamicName[pwrFolderLabelOffset], txPwrDyn);
503 pwrFolderDynamicName[pwrFolderLabelOffset++] = ')';
504 pwrFolderDynamicName[pwrFolderLabelOffset] = '\0';
507 static void updateFolderName_VtxAdmin()
509 uint8_t vtxBand = config.GetVtxBand();
510 if (vtxBand)
512 luaVtxFolder.dyn_name = vtxFolderDynamicName;
513 uint8_t vtxFolderLabelOffset = 11; // start writing after "VTX Admin ("
515 // Band
516 vtxFolderLabelOffset += findLuaSelectionLabel(&luaVtxBand, &vtxFolderDynamicName[vtxFolderLabelOffset], vtxBand);
517 vtxFolderDynamicName[vtxFolderLabelOffset++] = folderNameSeparator[1];
519 // Channel
520 vtxFolderDynamicName[vtxFolderLabelOffset++] = '1' + config.GetVtxChannel();
522 // VTX Power
523 uint8_t vtxPwr = config.GetVtxPower();
524 //if power is no-change (-), don't show, also hide pitmode
525 if (vtxPwr)
527 vtxFolderDynamicName[vtxFolderLabelOffset++] = folderNameSeparator[1];
528 vtxFolderLabelOffset += findLuaSelectionLabel(&luaVtxPwr, &vtxFolderDynamicName[vtxFolderLabelOffset], vtxPwr);
530 // Pit Mode
531 uint8_t vtxPit = config.GetVtxPitmode();
532 //if pitmode is off, don't show
533 //show pitmode AuxSwitch or show P if not OFF
534 if (vtxPit != 0)
536 if (vtxPit != 1)
538 vtxFolderDynamicName[vtxFolderLabelOffset++] = folderNameSeparator[1];
539 vtxFolderLabelOffset += findLuaSelectionLabel(&luaVtxPit, &vtxFolderDynamicName[vtxFolderLabelOffset], vtxPit);
541 else
543 vtxFolderDynamicName[vtxFolderLabelOffset++] = folderNameSeparator[1];
544 vtxFolderDynamicName[vtxFolderLabelOffset++] = 'P';
548 vtxFolderDynamicName[vtxFolderLabelOffset++] = ')';
549 vtxFolderDynamicName[vtxFolderLabelOffset] = '\0';
551 else
553 //don't show vtx settings if band is OFF
554 luaVtxFolder.dyn_name = NULL;
558 /***
559 * @brief: Update the luaBadGoodString with the current bad/good count
560 * This item is hidden on our Lua and only displayed in other systems that don't poll our status
561 * Called from luaRegisterDevicePingCallback
562 ****/
563 static void luadevUpdateBadGood()
565 itoa(CRSFHandset::BadPktsCountResult, luaBadGoodString, 10);
566 strcat(luaBadGoodString, "/");
567 itoa(CRSFHandset::GoodPktsCountResult, luaBadGoodString + strlen(luaBadGoodString), 10);
570 /***
571 * @brief: Update the dynamic strings used for folder names and labels
572 ***/
573 void luadevUpdateFolderNames()
575 updateFolderName_TxPower();
576 updateFolderName_VtxAdmin();
578 // These aren't folder names, just string labels slapped in the units field generally
579 luadevUpdateTlmBandwidth();
580 luadevUpdateBackpackOpts();
583 static void recalculatePacketRateOptions(int minInterval)
585 const char *allRates = STR_LUA_PACKETRATES;
586 const char *pos = allRates;
587 luastrPacketRates[0] = 0;
588 for (int i=0 ; i < RATE_MAX ; i++)
590 uint8_t rate = i;
591 rate = RATE_MAX - 1 - rate;
592 bool rateAllowed = get_elrs_airRateConfig(rate)->interval >= minInterval;
593 const char *semi = strchrnul(pos, ';');
594 if (rateAllowed)
596 strncat(luastrPacketRates, pos, semi - pos);
598 pos = semi;
599 if (*semi == ';')
601 strcat(luastrPacketRates, ";");
602 pos = semi+1;
606 // trim off trailing semicolons (assumes luastrPacketRates has at least 1 non-semicolon)
607 for (auto lastPos = strlen(luastrPacketRates)-1; luastrPacketRates[lastPos] == ';'; lastPos--)
609 luastrPacketRates[lastPos] = '\0';
613 uint8_t adjustSwitchModeForAirRate(OtaSwitchMode_e eSwitchMode, uint8_t packetSize)
615 // Only the fullres modes have 3 switch modes, so reset the switch mode if outside the
616 // range for 4ch mode
617 if (packetSize == OTA4_PACKET_SIZE)
619 if (eSwitchMode > smHybridOr16ch)
620 return smWideOr8ch;
623 return eSwitchMode;
626 static void registerLuaParameters()
628 if (HAS_RADIO) {
629 registerLUAParameter(&luaAirRate, [](struct luaPropertiesCommon *item, uint8_t arg) {
630 if (arg < RATE_MAX)
632 uint8_t selectedRate = RATE_MAX - 1 - arg;
633 uint8_t actualRate = adjustPacketRateForBaud(selectedRate);
634 uint8_t newSwitchMode = adjustSwitchModeForAirRate(
635 (OtaSwitchMode_e)config.GetSwitchMode(), get_elrs_airRateConfig(actualRate)->PayloadLength);
636 // If the switch mode is going to change, block the change while connected
637 bool isDisconnected = connectionState == disconnected;
638 // Don't allow the switch mode to change if the TX is in mavlink mode
639 // Wide switchmode is not compatible with mavlink, and the switchmode is
640 // auto configuredwhen entering mavlink mode
641 bool isMavlinkMode = config.GetLinkMode() == TX_MAVLINK_MODE;
642 if (newSwitchMode == OtaSwitchModeCurrent || (isDisconnected && !isMavlinkMode))
644 config.SetRate(actualRate);
645 config.SetSwitchMode(newSwitchMode);
646 if (actualRate != selectedRate)
648 setLuaWarningFlag(LUA_FLAG_ERROR_BAUDRATE, true);
651 else
652 setLuaWarningFlag(LUA_FLAG_ERROR_CONNECTED, true);
655 registerLUAParameter(&luaTlmRate, [](struct luaPropertiesCommon *item, uint8_t arg) {
656 expresslrs_tlm_ratio_e eRatio = (expresslrs_tlm_ratio_e)arg;
657 if (eRatio <= TLM_RATIO_DISARMED)
659 bool isMavlinkMode = config.GetLinkMode() == TX_MAVLINK_MODE;
660 // Don't allow TLM ratio changes if using AIRPORT or Mavlink
661 if (!firmwareOptions.is_airport && !isMavlinkMode)
663 config.SetTlm(eRatio);
667 #if defined(TARGET_TX_FM30)
668 registerLUAParameter(&luaBluetoothTelem, [](struct luaPropertiesCommon *item, uint8_t arg) {
669 digitalWrite(GPIO_PIN_BLUETOOTH_EN, !arg);
670 devicesTriggerEvent();
672 #endif
673 if (!firmwareOptions.is_airport)
675 registerLUAParameter(&luaSwitch, [](struct luaPropertiesCommon *item, uint8_t arg) {
676 // Only allow changing switch mode when disconnected since we need to guarantee
677 // the pack and unpack functions are matched
678 bool isDisconnected = connectionState == disconnected;
679 // Don't allow the switch mode to change if the TX is in mavlink mode
680 // Wide switchmode is not compatible with mavlink, and the switchmode is
681 // auto configuredwhen entering mavlink mode
682 bool isMavlinkMode = config.GetLinkMode() == TX_MAVLINK_MODE;
683 if (isDisconnected && !isMavlinkMode)
685 config.SetSwitchMode(arg);
686 OtaUpdateSerializers((OtaSwitchMode_e)arg, ExpressLRS_currAirRate_Modparams->PayloadLength);
688 else if (!isMavlinkMode) // No need to display warning as no switch change can be made while in Mavlink mode.
690 setLuaWarningFlag(LUA_FLAG_ERROR_CONNECTED, true);
694 if (isDualRadio())
696 registerLUAParameter(&luaAntenna, [](struct luaPropertiesCommon *item, uint8_t arg) {
697 config.SetAntennaMode(arg);
700 registerLUAParameter(&luaLinkMode, [](struct luaPropertiesCommon *item, uint8_t arg) {
701 // Only allow changing when disconnected since we need to guarantee
702 // the switch pack and unpack functions are matched on the tx and rx.
703 bool isDisconnected = connectionState == disconnected;
704 if (isDisconnected)
706 config.SetLinkMode(arg);
708 else
710 setLuaWarningFlag(LUA_FLAG_ERROR_CONNECTED, true);
713 if (!firmwareOptions.is_airport)
715 registerLUAParameter(&luaModelMatch, [](struct luaPropertiesCommon *item, uint8_t arg) {
716 bool newModelMatch = arg;
717 config.SetModelMatch(newModelMatch);
718 if (connectionState == connected)
720 mspPacket_t msp;
721 msp.reset();
722 msp.makeCommand();
723 msp.function = MSP_SET_RX_CONFIG;
724 msp.addByte(MSP_ELRS_MODEL_ID);
725 msp.addByte(newModelMatch ? CRSFHandset::getModelID() : 0xff);
726 CRSF::AddMspMessage(&msp, CRSF_ADDRESS_CRSF_RECEIVER);
728 luadevUpdateModelID();
732 // POWER folder
733 registerLUAParameter(&luaPowerFolder);
734 luadevGeneratePowerOpts(&luaPower);
735 registerLUAParameter(&luaPower, [](struct luaPropertiesCommon *item, uint8_t arg) {
736 config.SetPower((PowerLevels_e)constrain(arg + POWERMGNT::getMinPower(), POWERMGNT::getMinPower(), POWERMGNT::getMaxPower()));
737 if (!config.IsModified())
739 ResetPower();
741 }, luaPowerFolder.common.id);
742 registerLUAParameter(&luaDynamicPower, [](struct luaPropertiesCommon *item, uint8_t arg) {
743 config.SetDynamicPower(arg > 0);
744 config.SetBoostChannel((arg - 1) > 0 ? arg - 1 : 0);
745 }, luaPowerFolder.common.id);
747 if (GPIO_PIN_FAN_EN != UNDEF_PIN || GPIO_PIN_FAN_PWM != UNDEF_PIN) {
748 registerLUAParameter(&luaFanThreshold, [](struct luaPropertiesCommon *item, uint8_t arg){
749 config.SetPowerFanThreshold(arg);
750 }, luaPowerFolder.common.id);
752 #if defined(Regulatory_Domain_EU_CE_2400)
753 if (HAS_RADIO) {
754 registerLUAParameter(&luaCELimit, NULL, luaPowerFolder.common.id);
756 #endif
757 if ((HAS_RADIO || OPT_USE_TX_BACKPACK) && !firmwareOptions.is_airport) {
758 // VTX folder
759 registerLUAParameter(&luaVtxFolder);
760 registerLUAParameter(&luaVtxBand, [](struct luaPropertiesCommon *item, uint8_t arg) {
761 config.SetVtxBand(arg);
762 }, luaVtxFolder.common.id);
763 registerLUAParameter(&luaVtxChannel, [](struct luaPropertiesCommon *item, uint8_t arg) {
764 config.SetVtxChannel(arg - 1);
765 }, luaVtxFolder.common.id);
766 registerLUAParameter(&luaVtxPwr, [](struct luaPropertiesCommon *item, uint8_t arg) {
767 config.SetVtxPower(arg);
768 }, luaVtxFolder.common.id);
769 registerLUAParameter(&luaVtxPit, [](struct luaPropertiesCommon *item, uint8_t arg) {
770 config.SetVtxPitmode(arg);
771 }, luaVtxFolder.common.id);
772 registerLUAParameter(&luaVtxSend, &luahandSimpleSendCmd, luaVtxFolder.common.id);
775 // WIFI folder
776 #if defined(PLATFORM_ESP32) || defined(PLATFORM_ESP8266)
777 registerLUAParameter(&luaWiFiFolder);
778 registerLUAParameter(&luaWebUpdate, &luahandWifiBle, luaWiFiFolder.common.id);
779 #else
780 if (HAS_RADIO || OPT_USE_TX_BACKPACK) {
781 registerLUAParameter(&luaWiFiFolder);
783 #endif
784 if (HAS_RADIO) {
785 registerLUAParameter(&luaRxWebUpdate, &luahandSimpleSendCmd, luaWiFiFolder.common.id);
787 if (OPT_USE_TX_BACKPACK) {
788 registerLUAParameter(&luaTxBackpackUpdate, &luahandSimpleSendCmd, luaWiFiFolder.common.id);
789 registerLUAParameter(&luaVRxBackpackUpdate, &luahandSimpleSendCmd, luaWiFiFolder.common.id);
790 // Backpack folder
791 registerLUAParameter(&luaBackpackFolder);
792 #if defined(GPIO_PIN_BACKPACK_EN)
793 if (GPIO_PIN_BACKPACK_EN != UNDEF_PIN)
795 registerLUAParameter(
796 &luaBackpackEnable, [](luaPropertiesCommon *item, uint8_t arg) {
797 // option is Off/On (enable) and config storage is On/Off (disable)
798 config.SetBackpackDisable(arg == 0);
799 }, luaBackpackFolder.common.id);
801 #endif
802 registerLUAParameter(
803 &luaDvrAux, [](luaPropertiesCommon *item, uint8_t arg) {
804 if (config.GetBackpackDisable() == false)
805 config.SetDvrAux(arg);
807 luaBackpackFolder.common.id);
808 registerLUAParameter(
809 &luaDvrStartDelay, [](luaPropertiesCommon *item, uint8_t arg) {
810 if (config.GetBackpackDisable() == false)
811 config.SetDvrStartDelay(arg);
813 luaBackpackFolder.common.id);
814 registerLUAParameter(
815 &luaDvrStopDelay, [](luaPropertiesCommon *item, uint8_t arg) {
816 if (config.GetBackpackDisable() == false)
817 config.SetDvrStopDelay(arg);
819 luaBackpackFolder.common.id);
820 registerLUAParameter(
821 &luaHeadTrackingEnableChannel, [](luaPropertiesCommon *item, uint8_t arg) {
822 config.SetPTREnableChannel(arg);
824 luaBackpackFolder.common.id);
825 registerLUAParameter(
826 &luaHeadTrackingStartChannel, [](luaPropertiesCommon *item, uint8_t arg) {
827 config.SetPTRStartChannel(arg);
829 luaBackpackFolder.common.id);
830 registerLUAParameter(
831 &luaBackpackTelemetry, [](luaPropertiesCommon *item, uint8_t arg) {
832 config.SetBackpackTlmEnabled(arg);
833 }, luaBackpackFolder.common.id);
835 registerLUAParameter(&luaBackpackVersion, nullptr, luaBackpackFolder.common.id);
839 #if defined(PLATFORM_ESP32)
840 registerLUAParameter(&luaBLEJoystick, &luahandWifiBle);
841 #endif
843 if (HAS_RADIO) {
844 registerLUAParameter(&luaBind, &luahandSimpleSendCmd);
847 registerLUAParameter(&luaInfo);
848 if (strlen(version) < 21) {
849 strlcpy(version_domain, version, 21);
850 strlcat(version_domain, " ", sizeof(version_domain));
851 } else {
852 strlcpy(version_domain, version, 18);
853 strlcat(version_domain, "... ", sizeof(version_domain));
855 strlcat(version_domain, FHSSconfig->domain, sizeof(version_domain));
856 registerLUAParameter(&luaELRSversion);
857 registerLUAParameter(NULL);
860 static int event()
862 if (connectionState > FAILURE_STATES)
864 return DURATION_NEVER;
867 bool isMavlinkMode = config.GetLinkMode() == TX_MAVLINK_MODE;
868 uint8_t currentRate = adjustPacketRateForBaud(config.GetRate());
869 recalculatePacketRateOptions(handset->getMinPacketInterval());
870 setLuaTextSelectionValue(&luaAirRate, RATE_MAX - 1 - currentRate);
872 setLuaTextSelectionValue(&luaTlmRate, config.GetTlm());
873 luaTlmRate.options = isMavlinkMode ? tlmRatiosMav : tlmRatios;
875 setLuaTextSelectionValue(&luaSwitch, config.GetSwitchMode());
876 if (isMavlinkMode)
878 luaSwitch.options = OtaIsFullRes ? switchmodeOpts8chMav : switchmodeOpts4chMav;
880 else
882 luaSwitch.options = OtaIsFullRes ? switchmodeOpts8ch : switchmodeOpts4ch;
885 if (isDualRadio())
887 setLuaTextSelectionValue(&luaAntenna, config.GetAntennaMode());
889 setLuaTextSelectionValue(&luaLinkMode, config.GetLinkMode());
890 luadevUpdateModelID();
891 setLuaTextSelectionValue(&luaModelMatch, (uint8_t)config.GetModelMatch());
892 setLuaTextSelectionValue(&luaPower, config.GetPower() - MinPower);
893 if (GPIO_PIN_FAN_EN != UNDEF_PIN || GPIO_PIN_FAN_PWM != UNDEF_PIN)
895 setLuaTextSelectionValue(&luaFanThreshold, config.GetPowerFanThreshold());
898 uint8_t dynamic = config.GetDynamicPower() ? config.GetBoostChannel() + 1 : 0;
899 setLuaTextSelectionValue(&luaDynamicPower, dynamic);
901 setLuaTextSelectionValue(&luaVtxBand, config.GetVtxBand());
902 setLuaUint8Value(&luaVtxChannel, config.GetVtxChannel() + 1);
903 setLuaTextSelectionValue(&luaVtxPwr, config.GetVtxPower());
904 setLuaTextSelectionValue(&luaVtxPit, config.GetVtxPitmode());
905 if (OPT_USE_TX_BACKPACK)
907 #if defined(GPIO_PIN_BACKPACK_EN)
908 setLuaTextSelectionValue(&luaBackpackEnable, config.GetBackpackDisable() ? 0 : 1);
909 #endif
910 setLuaTextSelectionValue(&luaDvrAux, config.GetBackpackDisable() ? 0 : config.GetDvrAux());
911 setLuaTextSelectionValue(&luaDvrStartDelay, config.GetBackpackDisable() ? 0 : config.GetDvrStartDelay());
912 setLuaTextSelectionValue(&luaDvrStopDelay, config.GetBackpackDisable() ? 0 : config.GetDvrStopDelay());
913 setLuaTextSelectionValue(&luaHeadTrackingEnableChannel, config.GetBackpackDisable() ? 0 : config.GetPTREnableChannel());
914 setLuaTextSelectionValue(&luaHeadTrackingStartChannel, config.GetBackpackDisable() ? 0 : config.GetPTRStartChannel());
915 setLuaTextSelectionValue(&luaBackpackTelemetry, config.GetBackpackTlmEnabled() ? 1 : 0);
916 setLuaStringValue(&luaBackpackVersion, backpackVersion);
918 #if defined(TARGET_TX_FM30)
919 setLuaTextSelectionValue(&luaBluetoothTelem, !digitalRead(GPIO_PIN_BLUETOOTH_EN));
920 #endif
921 luadevUpdateFolderNames();
922 return DURATION_IMMEDIATELY;
925 static int timeout()
927 if (luaHandleUpdateParameter())
929 SetSyncSpam();
931 return DURATION_IMMEDIATELY;
934 static int start()
936 if (connectionState > FAILURE_STATES)
938 return DURATION_NEVER;
940 handset->registerParameterUpdateCallback(luaParamUpdateReq);
941 registerLuaParameters();
943 setLuaStringValue(&luaInfo, luaBadGoodString);
944 luaRegisterDevicePingCallback(&luadevUpdateBadGood);
946 event();
947 return DURATION_IMMEDIATELY;
950 device_t LUA_device = {
951 .initialize = NULL,
952 .start = start,
953 .event = event,
954 .timeout = timeout
957 #endif