Merge pull request #1269 from pkendall64/crsf-max-output
[ExpressLRS.git] / src / lib / LUA / devLUA.cpp
blob0758367cf766178a410aae891b86613806dbddc9
1 #ifdef TARGET_TX
3 #include "common.h"
4 #include "device.h"
6 #include "CRSF.h"
7 #include "POWERMGNT.h"
8 #include "config.h"
9 #include "logging.h"
10 #include "lua.h"
11 #include "OTA.h"
12 #include "hwTimer.h"
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;
20 #else
21 #error "Radio configuration is not valid!"
22 #endif
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},
29 0, // value
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)",
34 #endif
35 "Hz"
38 static struct luaItem_selection luaTlmRate = {
39 {"Telem Ratio", CRSF_TEXT_SELECTION},
40 0, // value
41 "Off;1:128;1:64;1:32;1:16;1:8;1:4;1:2",
42 emptySpace
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},
52 0, // value
53 strPowerLevels,
54 "mW"
57 static struct luaItem_selection luaDynamicPower = {
58 {"Dynamic", CRSF_TEXT_SELECTION},
59 0, // value
60 "Off;On;AUX9;AUX10;AUX11;AUX12",
61 emptySpace
64 #if defined(GPIO_PIN_FAN_EN)
65 static struct luaItem_selection luaFanThreshold = {
66 {"Fan Thresh", CRSF_TEXT_SELECTION},
67 0, // value
68 "10mW;25mW;50mW;100mW;250mW;500mW;1000mW;2000mW;Never",
69 emptySpace // units embedded so it won't display "NevermW"
71 #endif
73 //----------------------------POWER------------------
75 static struct luaItem_selection luaSwitch = {
76 {"Switch Mode", CRSF_TEXT_SELECTION},
77 0, // value
78 "Hybrid;Wide",
79 emptySpace
82 static struct luaItem_selection luaModelMatch = {
83 {"Model Match", CRSF_TEXT_SELECTION},
84 0, // value
85 "Off;On",
86 emptySpace
89 static struct luaItem_command luaBind = {
90 {"Bind", CRSF_COMMAND},
91 0, // step
92 emptySpace
95 static struct luaItem_string luaInfo = {
96 {"Bad/Good", (crsf_value_type_e)(CRSF_INFO | CRSF_FIELD_ELRS_HIDDEN)},
97 emptySpace
100 static struct luaItem_string luaELRSversion = {
101 {version, CRSF_INFO},
102 commit
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},
113 0, // step
114 emptySpace
116 #endif
118 static struct luaItem_command luaRxWebUpdate = {
119 {"Enable Rx WiFi", CRSF_COMMAND},
120 0, // step
121 emptySpace
124 #if defined(USE_TX_BACKPACK)
125 static struct luaItem_command luaTxBackpackUpdate = {
126 {"Enable Backpack WiFi", CRSF_COMMAND},
127 0, // step
128 emptySpace
131 static struct luaItem_command luaVRxBackpackUpdate = {
132 {"Enable VRx WiFi", CRSF_COMMAND},
133 0, // step
134 emptySpace
136 #endif // USE_TX_BACKPACK
137 //---------------------------- WiFi -----------------------------
139 #if defined(PLATFORM_ESP32)
140 static struct luaItem_command luaBLEJoystick = {
141 {"BLE Joystick", CRSF_COMMAND},
142 0, // step
143 emptySpace
145 #endif
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},
154 0, // value
155 "Off;A;B;E;F;R;L",
156 emptySpace
159 static struct luaItem_selection luaVtxChannel = {
160 {"Channel", CRSF_TEXT_SELECTION},
161 0, // value
162 "1;2;3;4;5;6;7;8",
163 emptySpace
166 static struct luaItem_selection luaVtxPwr = {
167 {"Pwr Lvl", CRSF_TEXT_SELECTION},
168 0, // value
169 "-;1;2;3;4;5;6;7;8",
170 emptySpace
173 static struct luaItem_selection luaVtxPit = {
174 {"Pitmode", CRSF_TEXT_SELECTION},
175 0, // value
176 "Off;On",
177 emptySpace
180 static struct luaItem_command luaVtxSend = {
181 {"Send VTx", CRSF_COMMAND},
182 0, // step
183 emptySpace
185 //----------------------------VTX ADMINISTRATOR------------------
187 #if defined(TARGET_TX_FM30)
188 struct luaItem_selection luaBluetoothTelem = {
189 {"BT Telemetry", CRSF_TEXT_SELECTION},
190 0, // value
191 "Off;On",
192 emptySpace
194 #endif
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;
210 #endif
211 #ifdef PLATFORM_ESP32
212 extern unsigned long rebootTime;
213 extern void beginWebsever();
214 #endif
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
237 if (*out)
238 ++out;
239 while (*out && *out != ';')
240 ++out;
241 pwr = (PowerLevels_e)((unsigned int)pwr + 1);
243 *out = '\0';
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();
267 #endif
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) {
284 mspPacket_t msp;
285 msp.reset();
286 msp.makeCommand();
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);
294 // POWER folder
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 }, luaPowerFolder.common.id);
308 #endif
309 // VTX folder
310 registerLUAParameter(&luaVtxFolder);
311 registerLUAParameter(&luaVtxBand, [](uint8_t id, uint8_t arg){
312 config.SetVtxBand(arg);
313 },luaVtxFolder.common.id);
314 registerLUAParameter(&luaVtxChannel, [](uint8_t id, uint8_t arg){
315 config.SetVtxChannel(arg);
316 },luaVtxFolder.common.id);
317 registerLUAParameter(&luaVtxPwr, [](uint8_t id, uint8_t arg){
318 config.SetVtxPower(arg);
319 },luaVtxFolder.common.id);
320 registerLUAParameter(&luaVtxPit, [](uint8_t id, uint8_t arg){
321 config.SetVtxPitmode(arg);
322 },luaVtxFolder.common.id);
323 registerLUAParameter(&luaVtxSend, [](uint8_t id, uint8_t arg){
324 if (arg < 5) {
325 VtxTriggerSend();
327 sendLuaCommandResponse(&luaVtxSend, arg < 5 ? 2 : 0, arg < 5 ? "Sending..." : "");
328 },luaVtxFolder.common.id);
330 // WIFI folder
331 registerLUAParameter(&luaWiFiFolder);
332 #if defined(PLATFORM_ESP32)
333 registerLUAParameter(&luaWebUpdate, [](uint8_t id, uint8_t arg){
334 if (arg == 4) // 4 = request confirmed, start
336 //confirm run on ELRSv2.lua or start command from CRSF configurator,
337 //since ELRS LUA can do 2 step confirmation, it needs confirmation to start wifi to prevent stuck on
338 //unintentional button press.
339 sendLuaCommandResponse(&luaWebUpdate, 2, "Wifi Running...");
340 connectionState = wifiUpdate;
342 else if (arg > 0 && arg < 4)
344 sendLuaCommandResponse(&luaWebUpdate, 3, "Enter WiFi Update Mode?");
346 else if (arg == 5)
348 sendLuaCommandResponse(&luaWebUpdate, 0, "WiFi Cancelled");
349 if (connectionState == wifiUpdate) {
350 rebootTime = millis() + 400;
353 else
355 sendLuaCommandResponse(&luaWebUpdate, luaWebUpdate.step, luaWebUpdate.info);
357 },luaWiFiFolder.common.id);
358 #endif
360 registerLUAParameter(&luaRxWebUpdate, [](uint8_t id, uint8_t arg){
361 if (arg < 5) {
362 RxWiFiReadyToSend = true;
364 sendLuaCommandResponse(&luaRxWebUpdate, arg < 5 ? 2 : 0, arg < 5 ? "Sending..." : "");
365 },luaWiFiFolder.common.id);
367 #if defined(USE_TX_BACKPACK)
368 registerLUAParameter(&luaTxBackpackUpdate, [](uint8_t id, uint8_t arg){
369 if (arg < 5) {
370 TxBackpackWiFiReadyToSend = true;
372 sendLuaCommandResponse(&luaTxBackpackUpdate, arg < 5 ? 2 : 0, arg < 5 ? "Sending..." : "");
373 },luaWiFiFolder.common.id);
375 registerLUAParameter(&luaVRxBackpackUpdate, [](uint8_t id, uint8_t arg){
376 if (arg < 5) {
377 VRxBackpackWiFiReadyToSend = true;
379 sendLuaCommandResponse(&luaVRxBackpackUpdate, arg < 5 ? 2 : 0, arg < 5 ? "Sending..." : "");
380 },luaWiFiFolder.common.id);
381 #endif // USE_TX_BACKPACK
383 #if defined(PLATFORM_ESP32)
384 registerLUAParameter(&luaBLEJoystick, [](uint8_t id, uint8_t arg){
385 if (arg == 4) // 4 = request confirmed, start
387 //confirm run on ELRSv2.lua or start command from CRSF configurator,
388 //since ELRS LUA can do 2 step confirmation, it needs confirmation to start BLE to prevent stuck on
389 //unintentional button press.
390 sendLuaCommandResponse(&luaBLEJoystick, 2, "Joystick Running...");
391 connectionState = bleJoystick;
393 else if (arg > 0 && arg < 4) //start command, 1 = start, 2 = running, 3 = request confirmation
395 sendLuaCommandResponse(&luaBLEJoystick, 3, "Start BLE Joystick?");
397 else if (arg == 5)
399 sendLuaCommandResponse(&luaBLEJoystick, 0, "Joystick Cancelled");
400 if (connectionState == bleJoystick) {
401 rebootTime = millis() + 400;
404 else
406 sendLuaCommandResponse(&luaBLEJoystick, luaBLEJoystick.step, luaBLEJoystick.info);
410 #endif
412 registerLUAParameter(&luaBind, [](uint8_t id, uint8_t arg){
413 if (arg < 5) {
414 EnterBindingMode();
416 sendLuaCommandResponse(&luaBind, arg < 5 ? 2 : 0, arg < 5 ? "Binding..." : "");
419 registerLUAParameter(&luaInfo);
420 registerLUAParameter(&luaELRSversion);
421 registerLUAParameter(NULL);
424 static int event()
426 setLuaWarningFlag(LUA_FLAG_MODEL_MATCH, connectionState == connected && connectionHasModelMatch == false);
427 setLuaWarningFlag(LUA_FLAG_CONNECTED, connectionState == connected);
428 uint8_t rate = adjustPacketRateForBaud(config.GetRate());
429 setLuaTextSelectionValue(&luaAirRate, RATE_MAX - 1 - rate);
430 setLuaTextSelectionValue(&luaTlmRate, config.GetTlm());
431 setLuaTextSelectionValue(&luaSwitch,(uint8_t)(config.GetSwitchMode() - 1)); // -1 for missing sm1Bit
432 setLuaTextSelectionValue(&luaModelMatch,(uint8_t)config.GetModelMatch());
433 setLuaTextSelectionValue(&luaPower, config.GetPower() - MinPower);
434 #if defined(GPIO_PIN_FAN_EN)
435 setLuaTextSelectionValue(&luaFanThreshold, config.GetPowerFanThreshold());
436 #endif
438 uint8_t dynamic = config.GetDynamicPower() ? config.GetBoostChannel() + 1 : 0;
439 setLuaTextSelectionValue(&luaDynamicPower,dynamic);
441 setLuaTextSelectionValue(&luaVtxBand,config.GetVtxBand());
442 setLuaTextSelectionValue(&luaVtxChannel,config.GetVtxChannel());
443 setLuaTextSelectionValue(&luaVtxPwr,config.GetVtxPower());
444 setLuaTextSelectionValue(&luaVtxPit,config.GetVtxPitmode());
445 #if defined(TARGET_TX_FM30)
446 setLuaTextSelectionValue(&luaBluetoothTelem, !digitalRead(GPIO_PIN_BLUETOOTH_EN));
447 #endif
448 return DURATION_IMMEDIATELY;
451 static int timeout()
453 if(luaHandleUpdateParameter())
455 SetSyncSpam();
457 return DURATION_IMMEDIATELY;
460 static int start()
462 CRSF::RecvParameterUpdate = &luaParamUpdateReq;
463 registerLuaParameters();
464 registerLUAPopulateParams([](){
465 itoa(CRSF::BadPktsCountResult, luaBadGoodString, 10);
466 strcat(luaBadGoodString, "/");
467 itoa(CRSF::GoodPktsCountResult, luaBadGoodString + strlen(luaBadGoodString), 10);
468 setLuaStringValue(&luaInfo, luaBadGoodString);
470 event();
471 return DURATION_IMMEDIATELY;
474 device_t LUA_device = {
475 .initialize = NULL,
476 .start = start,
477 .event = event,
478 .timeout = timeout
481 #endif