14 #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)
15 #include "SX127xDriver.h"
16 extern SX127xDriver Radio
;
17 #elif defined(Regulatory_Domain_ISM_2400)
18 #include "SX1280Driver.h"
19 extern SX1280Driver Radio
;
21 #error "Radio configuration is not valid!"
24 static const char emptySpace
[1] = {0};
25 static char strPowerLevels
[] = "10;25;50;100;250;500;1000;2000";
27 static struct luaItem_selection luaAirRate
= {
28 {"Packet Rate", CRSF_TEXT_SELECTION
},
30 #if defined(Regulatory_Domain_AU_915) || defined(Regulatory_Domain_EU_868) || defined(Regulatory_Domain_FCC_915) || defined(Regulatory_Domain_IN_866) || defined(Regulatory_Domain_AU_433) || defined(Regulatory_Domain_EU_433)
31 "25(-123dbm);50(-120dbm);100(-117dbm);200(-112dbm)",
32 #elif defined(Regulatory_Domain_ISM_2400)
33 "50(-117dbm);150(-112dbm);250(-108dbm);500(-105dbm)",
38 static struct luaItem_selection luaTlmRate
= {
39 {"Telem Ratio", CRSF_TEXT_SELECTION
},
41 "Off;1:128;1:64;1:32;1:16;1:8;1:4;1:2",
45 //----------------------------POWER------------------
46 static struct luaItem_folder luaPowerFolder
= {
47 {"TX Power", CRSF_FOLDER
},
50 static struct luaItem_selection luaPower
= {
51 {"Max Power", CRSF_TEXT_SELECTION
},
57 static struct luaItem_selection luaDynamicPower
= {
58 {"Dynamic", CRSF_TEXT_SELECTION
},
60 "Off;On;AUX9;AUX10;AUX11;AUX12",
64 #if defined(GPIO_PIN_FAN_EN)
65 static struct luaItem_selection luaFanThreshold
= {
66 {"Fan Thresh", CRSF_TEXT_SELECTION
},
68 "10mW;25mW;50mW;100mW;250mW;500mW;1000mW;2000mW;Never",
69 emptySpace
// units embedded so it won't display "NevermW"
73 //----------------------------POWER------------------
75 static struct luaItem_selection luaSwitch
= {
76 {"Switch Mode", CRSF_TEXT_SELECTION
},
82 static struct luaItem_selection luaModelMatch
= {
83 {"Model Match", CRSF_TEXT_SELECTION
},
89 static struct luaItem_command luaBind
= {
90 {"Bind", CRSF_COMMAND
},
95 static struct luaItem_string luaInfo
= {
96 {"Bad/Good", (crsf_value_type_e
)(CRSF_INFO
| CRSF_FIELD_ELRS_HIDDEN
)},
100 static struct luaItem_string luaELRSversion
= {
101 {version
, CRSF_INFO
},
105 //---------------------------- WiFi -----------------------------
106 static struct luaItem_folder luaWiFiFolder
= {
107 {"WiFi Connectivity", CRSF_FOLDER
}
110 #if defined(PLATFORM_ESP32)
111 static struct luaItem_command luaWebUpdate
= {
112 {"Enable WiFi", CRSF_COMMAND
},
118 static struct luaItem_command luaRxWebUpdate
= {
119 {"Enable Rx WiFi", CRSF_COMMAND
},
124 #if defined(USE_TX_BACKPACK)
125 static struct luaItem_command luaTxBackpackUpdate
= {
126 {"Enable Backpack WiFi", CRSF_COMMAND
},
131 static struct luaItem_command luaVRxBackpackUpdate
= {
132 {"Enable VRx WiFi", CRSF_COMMAND
},
136 #endif // USE_TX_BACKPACK
137 //---------------------------- WiFi -----------------------------
139 #if defined(PLATFORM_ESP32)
140 static struct luaItem_command luaBLEJoystick
= {
141 {"BLE Joystick", CRSF_COMMAND
},
147 //----------------------------VTX ADMINISTRATOR------------------
148 static struct luaItem_folder luaVtxFolder
= {
149 {"VTX Administrator", CRSF_FOLDER
},
152 static struct luaItem_selection luaVtxBand
= {
153 {"Band", CRSF_TEXT_SELECTION
},
159 static struct luaItem_selection luaVtxChannel
= {
160 {"Channel", CRSF_TEXT_SELECTION
},
166 static struct luaItem_selection luaVtxPwr
= {
167 {"Pwr Lvl", CRSF_TEXT_SELECTION
},
173 static struct luaItem_selection luaVtxPit
= {
174 {"Pitmode", CRSF_TEXT_SELECTION
},
180 static struct luaItem_command luaVtxSend
= {
181 {"Send VTx", CRSF_COMMAND
},
185 //----------------------------VTX ADMINISTRATOR------------------
187 #if defined(TARGET_TX_FM30)
188 struct luaItem_selection luaBluetoothTelem
= {
189 {"BT Telemetry", CRSF_TEXT_SELECTION
},
197 static char luaBadGoodString
[10];
199 extern TxConfig config
;
200 extern void VtxTriggerSend();
201 extern uint8_t adjustPacketRateForBaud(uint8_t rate
);
202 extern void SetSyncSpam();
203 extern void EnterBindingMode();
204 extern bool InBindingMode
;
205 extern bool connectionHasModelMatch
;
206 extern bool RxWiFiReadyToSend
;
207 #if defined(USE_TX_BACKPACK)
208 extern bool TxBackpackWiFiReadyToSend
;
209 extern bool VRxBackpackWiFiReadyToSend
;
211 #ifdef PLATFORM_ESP32
212 extern unsigned long rebootTime
;
213 extern void beginWebsever();
216 static void luadevGeneratePowerOpts()
218 // This function modifies the strPowerLevels in place and must not
219 // be called more than once!
220 char *out
= strPowerLevels
;
221 PowerLevels_e pwr
= PWR_10mW
;
222 // Count the semicolons to move `out` to point to the MINth item
223 while (pwr
< MinPower
)
225 while (*out
++ != ';') ;
226 pwr
= (PowerLevels_e
)((unsigned int)pwr
+ 1);
228 // There is no min field, compensate by shifting the index when sending/receiving
229 // luaPower.min = (uint8_t)MinPower;
230 luaPower
.options
= (const char *)out
;
232 // Continue until after than MAXth item and drop a null in the orginal
233 // string on the semicolon (not after like the previous loop)
234 while (pwr
<= MaxPower
)
236 // If out still points to a semicolon from the last loop move past it
239 while (*out
&& *out
!= ';')
241 pwr
= (PowerLevels_e
)((unsigned int)pwr
+ 1);
246 static void registerLuaParameters()
248 registerLUAParameter(&luaAirRate
, [](uint8_t id
, uint8_t arg
){
249 if ((arg
< RATE_MAX
) && (arg
>= 0))
251 uint8_t rate
= RATE_MAX
- 1 - arg
;
252 rate
= adjustPacketRateForBaud(rate
);
253 config
.SetRate(rate
);
256 registerLUAParameter(&luaTlmRate
, [](uint8_t id
, uint8_t arg
){
257 if ((arg
<= (uint8_t)TLM_RATIO_1_2
) && (arg
>= (uint8_t)TLM_RATIO_NO_TLM
))
259 config
.SetTlm((expresslrs_tlm_ratio_e
)arg
);
262 #if defined(TARGET_TX_FM30)
263 registerLUAParameter(&luaBluetoothTelem
, [](uint8_t id
, uint8_t arg
) {
264 digitalWrite(GPIO_PIN_BLUETOOTH_EN
, !arg
);
265 devicesTriggerEvent();
268 registerLUAParameter(&luaSwitch
, [](uint8_t id
, uint8_t arg
){
269 // Only allow changing switch mode when disconnected since we need to guarantee
270 // the pack and unpack functions are matched
271 if (connectionState
== disconnected
)
273 // +1 to the mode because 1-bit was mode 0 and has been removed
274 // The modes should be updated for 1.1RC so mode 0 can be smHybrid
275 uint32_t newSwitchMode
= (arg
+ 1) & 0b11;
276 config
.SetSwitchMode(newSwitchMode
);
277 OtaSetSwitchMode((OtaSwitchMode_e
)newSwitchMode
);
280 registerLUAParameter(&luaModelMatch
, [](uint8_t id
, uint8_t arg
){
281 bool newModelMatch
= arg
;
282 config
.SetModelMatch(newModelMatch
);
283 if (connectionState
== connected
) {
287 msp
.function
= MSP_SET_RX_CONFIG
;
288 msp
.addByte(MSP_ELRS_MODEL_ID
);
289 msp
.addByte(newModelMatch
? CRSF::getModelID() : 0xff);
290 CRSF::AddMspMessage(&msp
);
295 registerLUAParameter(&luaPowerFolder
);
296 luadevGeneratePowerOpts();
297 registerLUAParameter(&luaPower
, [](uint8_t id
, uint8_t arg
){
298 config
.SetPower((PowerLevels_e
)constrain(arg
+ MinPower
, MinPower
, MaxPower
));
299 }, luaPowerFolder
.common
.id
);
300 registerLUAParameter(&luaDynamicPower
, [](uint8_t id
, uint8_t arg
){
301 config
.SetDynamicPower(arg
> 0);
302 config
.SetBoostChannel((arg
- 1) > 0 ? arg
- 1 : 0);
303 }, luaPowerFolder
.common
.id
);
304 #if defined(GPIO_PIN_FAN_EN)
305 registerLUAParameter(&luaFanThreshold
, [](uint8_t id
, uint8_t arg
){
306 config
.SetPowerFanThreshold(arg
);
307 POWERMGNT::setFanEnableTheshold((PowerLevels_e
)arg
);
308 }, luaPowerFolder
.common
.id
);
311 registerLUAParameter(&luaVtxFolder
);
312 registerLUAParameter(&luaVtxBand
, [](uint8_t id
, uint8_t arg
){
313 config
.SetVtxBand(arg
);
314 },luaVtxFolder
.common
.id
);
315 registerLUAParameter(&luaVtxChannel
, [](uint8_t id
, uint8_t arg
){
316 config
.SetVtxChannel(arg
);
317 },luaVtxFolder
.common
.id
);
318 registerLUAParameter(&luaVtxPwr
, [](uint8_t id
, uint8_t arg
){
319 config
.SetVtxPower(arg
);
320 },luaVtxFolder
.common
.id
);
321 registerLUAParameter(&luaVtxPit
, [](uint8_t id
, uint8_t arg
){
322 config
.SetVtxPitmode(arg
);
323 },luaVtxFolder
.common
.id
);
324 registerLUAParameter(&luaVtxSend
, [](uint8_t id
, uint8_t arg
){
328 sendLuaCommandResponse(&luaVtxSend
, arg
< 5 ? 2 : 0, arg
< 5 ? "Sending..." : "");
329 },luaVtxFolder
.common
.id
);
332 registerLUAParameter(&luaWiFiFolder
);
333 #if defined(PLATFORM_ESP32)
334 registerLUAParameter(&luaWebUpdate
, [](uint8_t id
, uint8_t arg
){
335 if (arg
== 4) // 4 = request confirmed, start
337 //confirm run on ELRSv2.lua or start command from CRSF configurator,
338 //since ELRS LUA can do 2 step confirmation, it needs confirmation to start wifi to prevent stuck on
339 //unintentional button press.
340 sendLuaCommandResponse(&luaWebUpdate
, 2, "Wifi Running...");
341 connectionState
= wifiUpdate
;
343 else if (arg
> 0 && arg
< 4)
345 sendLuaCommandResponse(&luaWebUpdate
, 3, "Enter WiFi Update Mode?");
349 sendLuaCommandResponse(&luaWebUpdate
, 0, "WiFi Cancelled");
350 if (connectionState
== wifiUpdate
) {
351 rebootTime
= millis() + 400;
356 sendLuaCommandResponse(&luaWebUpdate
, luaWebUpdate
.step
, luaWebUpdate
.info
);
358 },luaWiFiFolder
.common
.id
);
361 registerLUAParameter(&luaRxWebUpdate
, [](uint8_t id
, uint8_t arg
){
363 RxWiFiReadyToSend
= true;
365 sendLuaCommandResponse(&luaRxWebUpdate
, arg
< 5 ? 2 : 0, arg
< 5 ? "Sending..." : "");
366 },luaWiFiFolder
.common
.id
);
368 #if defined(USE_TX_BACKPACK)
369 registerLUAParameter(&luaTxBackpackUpdate
, [](uint8_t id
, uint8_t arg
){
371 TxBackpackWiFiReadyToSend
= true;
373 sendLuaCommandResponse(&luaTxBackpackUpdate
, arg
< 5 ? 2 : 0, arg
< 5 ? "Sending..." : "");
374 },luaWiFiFolder
.common
.id
);
376 registerLUAParameter(&luaVRxBackpackUpdate
, [](uint8_t id
, uint8_t arg
){
378 VRxBackpackWiFiReadyToSend
= true;
380 sendLuaCommandResponse(&luaVRxBackpackUpdate
, arg
< 5 ? 2 : 0, arg
< 5 ? "Sending..." : "");
381 },luaWiFiFolder
.common
.id
);
382 #endif // USE_TX_BACKPACK
384 #if defined(PLATFORM_ESP32)
385 registerLUAParameter(&luaBLEJoystick
, [](uint8_t id
, uint8_t arg
){
386 if (arg
== 4) // 4 = request confirmed, start
388 //confirm run on ELRSv2.lua or start command from CRSF configurator,
389 //since ELRS LUA can do 2 step confirmation, it needs confirmation to start BLE to prevent stuck on
390 //unintentional button press.
391 sendLuaCommandResponse(&luaBLEJoystick
, 2, "Joystick Running...");
392 connectionState
= bleJoystick
;
394 else if (arg
> 0 && arg
< 4) //start command, 1 = start, 2 = running, 3 = request confirmation
396 sendLuaCommandResponse(&luaBLEJoystick
, 3, "Start BLE Joystick?");
400 sendLuaCommandResponse(&luaBLEJoystick
, 0, "Joystick Cancelled");
401 if (connectionState
== bleJoystick
) {
402 rebootTime
= millis() + 400;
407 sendLuaCommandResponse(&luaBLEJoystick
, luaBLEJoystick
.step
, luaBLEJoystick
.info
);
413 registerLUAParameter(&luaBind
, [](uint8_t id
, uint8_t arg
){
417 sendLuaCommandResponse(&luaBind
, arg
< 5 ? 2 : 0, arg
< 5 ? "Binding..." : "");
420 registerLUAParameter(&luaInfo
);
421 registerLUAParameter(&luaELRSversion
);
422 registerLUAParameter(NULL
);
427 setLuaWarningFlag(LUA_FLAG_MODEL_MATCH
, connectionState
== connected
&& connectionHasModelMatch
== false);
428 setLuaWarningFlag(LUA_FLAG_CONNECTED
, connectionState
== connected
);
429 uint8_t rate
= adjustPacketRateForBaud(config
.GetRate());
430 setLuaTextSelectionValue(&luaAirRate
, RATE_MAX
- 1 - rate
);
431 setLuaTextSelectionValue(&luaTlmRate
, config
.GetTlm());
432 setLuaTextSelectionValue(&luaSwitch
,(uint8_t)(config
.GetSwitchMode() - 1)); // -1 for missing sm1Bit
433 setLuaTextSelectionValue(&luaModelMatch
,(uint8_t)config
.GetModelMatch());
434 setLuaTextSelectionValue(&luaPower
, config
.GetPower() - MinPower
);
435 #if defined(GPIO_PIN_FAN_EN)
436 setLuaTextSelectionValue(&luaFanThreshold
, config
.GetPowerFanThreshold());
439 uint8_t dynamic
= config
.GetDynamicPower() ? config
.GetBoostChannel() + 1 : 0;
440 setLuaTextSelectionValue(&luaDynamicPower
,dynamic
);
442 setLuaTextSelectionValue(&luaVtxBand
,config
.GetVtxBand());
443 setLuaTextSelectionValue(&luaVtxChannel
,config
.GetVtxChannel());
444 setLuaTextSelectionValue(&luaVtxPwr
,config
.GetVtxPower());
445 setLuaTextSelectionValue(&luaVtxPit
,config
.GetVtxPitmode());
446 #if defined(TARGET_TX_FM30)
447 setLuaTextSelectionValue(&luaBluetoothTelem
, !digitalRead(GPIO_PIN_BLUETOOTH_EN
));
449 return DURATION_IMMEDIATELY
;
454 if(luaHandleUpdateParameter())
458 return DURATION_IMMEDIATELY
;
463 CRSF::RecvParameterUpdate
= &luaParamUpdateReq
;
464 registerLuaParameters();
465 registerLUAPopulateParams([](){
466 itoa(CRSF::BadPktsCountResult
, luaBadGoodString
, 10);
467 strcat(luaBadGoodString
, "/");
468 itoa(CRSF::GoodPktsCountResult
, luaBadGoodString
+ strlen(luaBadGoodString
), 10);
469 setLuaStringValue(&luaInfo
, luaBadGoodString
);
472 return DURATION_IMMEDIATELY
;
475 device_t LUA_device
= {