diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 826514ebed..924978352e 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -39,8 +39,10 @@ jobs: - "esp32dev-rtl_433" - "esp32doitv1-aithinker-r01-sx1278" - "heltec-rtl_433" + - "heltec-rtl_433-fsk" - "heltec-ble" - "lilygo-rtl_433" + - "lilygo-rtl_433-fsk" - "lilygo-ble" - "esp32dev-multi_receiver" - "esp32dev-multi_receiver-pilight" diff --git a/docs/use/rf.md b/docs/use/rf.md index a5f48e64b6..2f1c08339c 100644 --- a/docs/use/rf.md +++ b/docs/use/rf.md @@ -124,19 +124,19 @@ Registering protocol [102] "X10 Security" ### Change receive frequency -Default receive frequency of the module is 433.92 Mhz, and this can be can changed by sending a message with the frequency. Parameter is `mhz` and valid values are 300-348 Mhz, 387-464Mhz and 779-928Mhz. Actual frequency support will depend on your board +The frequency can be can changed by sending an MQTT message or through the WebUI. Parameter is `frequency` and valid values are 300-348 Mhz, 387-464Mhz and 779-928Mhz. Actual frequency support will depend on your board -`home/OpenMQTTGateway/commands/MQTTtoRTL_433 {"mhz":315.026}` +`home/OpenMQTTGateway/commands/MQTTtoRF/config {"frequency":315.026}` ### Change Signal RSSI Threshold Delta Delta applied to RSSI floor noise level to determine start and end of signal, defaults to 9db. -`home/OpenMQTTGateway/commands/MQTTtoRTL_433 {"rssi": 9}` +`home/OpenMQTTGateway/commands/MQTTtoRF/config {"rssiThreshold": 9}` ### Retrieve current status of receiver -`home/OpenMQTTGateway/commands/MQTTtoRTL_433 {"status":1}` +`home/OpenMQTTGateway/commands/MQTTtoRF/config {"status":1}` ``` {"model":"status", @@ -159,41 +159,27 @@ Delta applied to RSSI floor noise level to determine start and end of signal, de "freeMem":112880} - ESP32 memory available ``` - ## Changing Active Receiver Modules ### Switching Active Receiver Module -Switching of the active transceiver (RTL_433 receiver only) module is available between the RF, RF2, RTL_433 and Pilight gateway modules, allowing for changing of signal decoders without redeploying the openMQTTGateway package. Sending a JSON message to the command topic of the desired receiver will change the active transceiver module. +Switching of the active transceiver (RTL_433 receiver only) module is available between the RF, RF2, and (RTL_433 or Pilight) gateway modules, allowing for changing of signal decoders without redeploying the OpenMQTTGateway package. Sending a JSON message to the command topic will change the active transceiver module. To enable the RF gateway module send a json message to the RF gateway module command subject with the key being 'active', and any value. The value at this time is ignored. -Example: -`mosquitto_pub -t "home/OpenMQTTGateway/commands/MQTTto433" -m '{"active":true}'` - -To enable the PiLight gateway module send a json message to the PiLight gateway module command subject with the key being 'active', and any value. The value at this time is ignored. - -Example: -`mosquitto_pub -t "home/OpenMQTTGateway/commands/MQTTtoPilight" -m '{"active":true}'` - -To enable the RF2 gateway module send a json message to the RF2 gateway module command subject with the key being 'active', and any value. The value at this time is ignored. - -Example: -`mosquitto_pub -t "home/OpenMQTTGateway/commands/MQTTtoRF2" -m '{"active":true}'` +1 - PiLight +2 - RF +3 - RTL_433 +4 - RF2 -To enable the RTL_433 gateway module send a json message to the RTL_433 gateway module command subject with the key being 'active', and any value. The value at this time is ignored. +Example to receive from the RF gateway: +`mosquitto_pub -t "home/OpenMQTTGateway/commands/MQTTtoRF/config" -m '{"active":2}'` -Example: -`mosquitto_pub -t "home/OpenMQTTGateway/commands/MQTTtoRTL_433" -m '{"active":true}'` +The active receiver can also be changed with the WebUI. ### Status Messages -The openMQTTGateway status message contains a key `actRec` which is the current active receiver module. - -1 - PiLight -2 - RF -3 - RTL_433 -4 - RF2 +The OpenMQTTGateway RFtoMQTT status message contains a key `active` which is the current active receiver module. ## RCSwitch based gateway diff --git a/environments.ini b/environments.ini index 27928300a2..b06ffe4e4a 100644 --- a/environments.ini +++ b/environments.ini @@ -728,6 +728,7 @@ board_build.partitions = min_spiffs.csv lib_deps = ${com-esp32.lib_deps} ${libraries.rtl_433_ESP} + ${libraries.smartrc-cc1101-driver-lib} build_flags = ${com-esp32.build_flags} ; *** OpenMQTTGateway Config *** @@ -787,6 +788,40 @@ build_flags = ; '-DDISPLAY_BRIGHTNESS=80' ; '-DDISPLAY_METRIC=false' custom_description = Gateway using RTL_433_ESP and RadioLib +custom_hardware = ESP32 HELTEC LORA32 V2 + +[env:heltec-rtl_433-fsk] +platform = ${com.esp32_platform} +board = heltec_wifi_lora_32_V2 +; ~/.platformio/packages/framework-arduinoespressif32/variants/.../pins_arduino.h +board_build.partitions = min_spiffs.csv +lib_deps = + ${com-esp32.lib_deps} + ${libraries.ssd1306} + ${libraries.rtl_433_ESP} +build_flags = + ${com-esp32.build_flags} +; *** OpenMQTTGateway Config *** + ;'-UZmqttDiscovery' ; disables MQTT Discovery + '-DvalueAsATopic=true' ; MQTT topic includes model and device + '-DGateway_Name="OMG_heltec_rtl_433_ESP"' + '-DOOK_MODULATION=false' ; FSK modulation activated + '-DRF_FREQUENCY=915' + ;-DRF_FREQUENCY=868.300' + ;-DRF_FREQUENCY=433.9' +; *** OpenMQTTGateway Modules *** + '-DZgatewayRTL_433="rtl_433"' + '-DZradioSX127x="SX127x"' +; *** ssd1306 Display Options *** + '-DZdisplaySSD1306="HELTEC_SSD1306"' +; '-DLOG_TO_OLED=false' ; Enable log to OLED +; '-DJSON_TO_OLED=true' +; '-DLOG_LEVEL_OLED=LOG_LEVEL_NOTICE' +; '-DDISPLAY_IDLE_LOGO=false' +; '-DDISPLAY_BRIGHTNESS=80' +; '-DDISPLAY_METRIC=false' +custom_description = Gateway using RTL_433_ESP and RadioLib +custom_hardware = ESP32 HELTEC LORA32 V2 [env:heltec-ble] platform = ${com.esp32_platform} @@ -810,6 +845,7 @@ build_flags = ; '-DDISPLAY_BRIGHTNESS=80' ; '-DDISPLAY_METRIC=false' custom_description = Heltec BLE gateway with adaptive scanning activated, automatically adapts the scan parameters depending on your devices +custom_hardware = ESP32 HELTEC LORA32 V2 [env:lilygo-rtl_433] platform = ${com.esp32_platform} @@ -840,6 +876,39 @@ build_flags = custom_description = For ESP32, Gateway using RTL_433_ESP and RadioLib custom_hardware = ESP32 LILYGO LoRa32 V2.1 +[env:lilygo-rtl_433-fsk] +platform = ${com.esp32_platform} +board = ttgo-lora32-v21 +; ~/.platformio/packages/framework-arduinoespressif32/variants/.../pins_arduino.h +board_build.partitions = min_spiffs.csv +lib_deps = + ${com-esp32.lib_deps} + ${libraries.ssd1306} + ${libraries.rtl_433_ESP} +build_flags = + ${com-esp32.build_flags} +; *** OpenMQTTGateway Config *** + ;'-UZmqttDiscovery' ; disables MQTT Discovery + '-DvalueAsATopic=true' ; MQTT topic includes model and device + '-DGateway_Name="OMG_lilygo_rtl_433_ESP"' + '-DOOK_MODULATION=false' ; FSK modulation activated + '-DRF_FREQUENCY=915' + ;-DRF_FREQUENCY=868.300' + ;-DRF_FREQUENCY=433.9' +; *** OpenMQTTGateway Modules *** + '-DZgatewayRTL_433="rtl_433"' + '-DZradioSX127x="SX127x"' +; *** ssd1306 Display Options *** + '-DZdisplaySSD1306="LilyGo_SSD1306"' +; '-DLOG_TO_OLED=true' ; Enable log to OLED +; '-DJSON_TO_OLED=true' +; '-DLOG_LEVEL_OLED=LOG_LEVEL_NOTICE' +; '-DDISPLAY_IDLE_LOGO=false' +; '-DDISPLAY_BRIGHTNESS=80' +; '-DDISPLAY_METRIC=false' +custom_description = For ESP32, Gateway using RTL_433_ESP and RadioLib with FSK modulation (beta) +custom_hardware = ESP32 LILYGO LoRa32 V2.1 + [env:lilygo-ble] platform = ${com.esp32_platform} board = ttgo-lora32-v21 @@ -920,7 +989,6 @@ build_flags = ; '-DRF_MODULE_INIT_STATUS=true' ; Display transceiver config during startup custom_description = Multi RF library with the possibility to switch between ESPilight, NewRemoteSwitch and RCSwitch, need CC1101 - [env:tinypico-ble] platform = ${com.esp32_platform} board = tinypico diff --git a/main/ZactuatorSomfy.ino b/main/ZactuatorSomfy.ino index 6e8b907463..8c0412b906 100644 --- a/main/ZactuatorSomfy.ino +++ b/main/ZactuatorSomfy.ino @@ -34,9 +34,6 @@ # endif void setupSomfy() { -# ifdef ZradioCC1101 //using with CC1101 - ELECHOUSE_cc1101.Init(); -# endif pinMode(RF_EMITTER_GPIO, OUTPUT); digitalWrite(RF_EMITTER_GPIO, LOW); @@ -55,7 +52,7 @@ void setupSomfy() { void MQTTtoSomfy(char* topicOri, JsonObject& jsonData) { if (cmpToMainTopic(topicOri, subjectMQTTtoSomfy)) { # ifdef ZradioCC1101 - ELECHOUSE_cc1101.SetTx(CC1101_FREQUENCY_SOMFY); + ELECHOUSE_cc1101.SetTx(RF_FREQUENCY_SOMFY); # endif Log.trace(F("MQTTtoSomfy json data analysis" CR)); @@ -72,9 +69,7 @@ void MQTTtoSomfy(char* topicOri, JsonObject& jsonData) { EEPROMRollingCodeStorage rollingCodeStorage(EEPROM_ADDRESS_START + remoteIndex * 2); SomfyRemote somfyRemote(RF_EMITTER_GPIO, somfyRemotes[remoteIndex], &rollingCodeStorage); somfyRemote.sendCommand(command, repeat); -# ifdef ZradioCC1101 - ELECHOUSE_cc1101.SetRx(receiveMhz); // set Receive on -# endif + initCC1101(); } } # endif diff --git a/main/ZcommonRF.ino b/main/ZcommonRF.ino new file mode 100644 index 0000000000..2aa7ccb057 --- /dev/null +++ b/main/ZcommonRF.ino @@ -0,0 +1,334 @@ +/* + OpenMQTTGateway - ESP8266 or Arduino program for home automation + + Act as a wifi or ethernet gateway between your BLE/433mhz/infrared IR signal and an MQTT broker + Send and receiving command by MQTT + + Copyright: (c)Florian ROBERT + + This file is part of OpenMQTTGateway. + + OpenMQTTGateway is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + OpenMQTTGateway is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +#include "User_config.h" + +#if defined(ZgatewayRF) || defined(ZgatewayPilight) || defined(ZgatewayRTL_433) || defined(ZgatewayRF2) || defined(ZactuatorSomfy) +# ifndef ARDUINO_AVR_UNO + +# ifdef ZradioCC1101 +# include +# endif + +void initCC1101() { +# ifdef ZradioCC1101 //receiving with CC1101 + // Loop on getCC1101() until it returns true and break after 10 attempts + for (int i = 0; i < 10; i++) { + if (ELECHOUSE_cc1101.getCC1101()) { + Log.notice(F("C1101 spi Connection OK" CR)); + ELECHOUSE_cc1101.Init(); + ELECHOUSE_cc1101.SetRx(RFConfig.frequency); + break; + } else { + Log.error(F("C1101 spi Connection Error" CR)); + delay(500); + } + } +# endif +} + +void setupCommonRF() { + RFConfig_init(); + RFConfig_load(); +} + +bool validFrequency(float mhz) { + // CC1101 valid frequencies 300-348 MHZ, 387-464MHZ and 779-928MHZ. + if (mhz >= 300 && mhz <= 348) + return true; + if (mhz >= 387 && mhz <= 464) + return true; + if (mhz >= 779 && mhz <= 928) + return true; + return false; +} + +int currentReceiver = ACTIVE_NONE; + +# if !defined(ZgatewayRFM69) && !defined(ZactuatorSomfy) +# if defined(ESP8266) || defined(ESP32) +// Check if a receiver is available +bool validReceiver(int receiver) { + switch (receiver) { +# ifdef ZgatewayPilight + case ACTIVE_PILIGHT: + return true; +# endif +# ifdef ZgatewayRF + case ACTIVE_RF: + return true; +# endif +# ifdef ZgatewayRTL_433 + case ACTIVE_RTL: + return true; +# endif +# ifdef ZgatewayRF2 + case ACTIVE_RF2: + return true; +# endif + default: + Log.error(F("ERROR: stored receiver %d not available" CR), receiver); + } + return false; +} +# endif +# endif + +void disableCurrentReceiver() { + Log.trace(F("disableCurrentReceiver: %d" CR), currentReceiver); + switch (currentReceiver) { + case ACTIVE_NONE: + break; +# ifdef ZgatewayPilight + case ACTIVE_PILIGHT: + disablePilightReceive(); + break; +# endif +# ifdef ZgatewayRF + case ACTIVE_RF: + disableRFReceive(); + break; +# endif +# ifdef ZgatewayRTL_433 + case ACTIVE_RTL: + disableRTLreceive(); + break; +# endif +# ifdef ZgatewayRF2 + case ACTIVE_RF2: + disableRF2Receive(); + break; +# endif +# ifndef ARDUINO_AVR_UNO // Space issues with the UNO + default: + Log.error(F("ERROR: unsupported receiver %d" CR), RFConfig.activeReceiver); +# endif + } +} + +void enableActiveReceiver() { + Log.trace(F("enableActiveReceiver: %d" CR), RFConfig.activeReceiver); + switch (RFConfig.activeReceiver) { +# ifdef ZgatewayPilight + case ACTIVE_PILIGHT: + initCC1101(); + enablePilightReceive(); + currentReceiver = ACTIVE_PILIGHT; + break; +# endif +# ifdef ZgatewayRF + case ACTIVE_RF: + initCC1101(); + enableRFReceive(); + currentReceiver = ACTIVE_RF; + break; +# endif +# ifdef ZgatewayRTL_433 + case ACTIVE_RTL: + initCC1101(); + enableRTLreceive(); + currentReceiver = ACTIVE_RTL; + break; +# endif +# ifdef ZgatewayRF2 + case ACTIVE_RF2: + initCC1101(); + enableRF2Receive(); + currentReceiver = ACTIVE_RF2; + break; +# endif + case ACTIVE_RECERROR: + Log.error(F("ERROR: no receiver selected" CR)); + break; +# ifndef ARDUINO_AVR_UNO // Space issues with the UNO + default: + Log.error(F("ERROR: unsupported receiver %d" CR), RFConfig.activeReceiver); +# endif + } +} + +String stateRFMeasures() { + //Publish RTL_433 state + StaticJsonDocument jsonBuffer; + JsonObject RFdata = jsonBuffer.to(); + RFdata["active"] = RFConfig.activeReceiver; +# if defined(ZradioCC1101) || defined(ZradioSX127x) + RFdata["frequency"] = RFConfig.frequency; + if (RFConfig.activeReceiver == ACTIVE_RTL) { +# ifdef ZgatewayRTL_433 + RFdata["rssithreshold"] = (int)getRTLrssiThreshold(); + RFdata["rssi"] = (int)getRTLCurrentRSSI(); + RFdata["avgrssi"] = (int)getRTLAverageRSSI(); + RFdata["count"] = (int)getRTLMessageCount(); +# endif +# ifdef ZradioSX127x + RFdata["ookthreshold"] = (int)getOOKThresh(); +# endif + } +# endif + pub(subjectcommonRFtoMQTT, RFdata); + + String output; + serializeJson(RFdata, output); + return output; +} + +void RFConfig_fromJson(JsonObject& RFdata) { + bool success = false; + if (RFdata.containsKey("frequency") && validFrequency(RFdata["frequency"])) { + Config_update(RFdata, "frequency", RFConfig.frequency); + Log.notice(F("RF Receive mhz: %F" CR), RFConfig.frequency); + success = true; + } + if (RFdata.containsKey("active")) { + Log.notice(F("RF receiver active: %d" CR), RFConfig.activeReceiver); + Config_update(RFdata, "active", RFConfig.activeReceiver); + success = true; + } +# ifdef ZgatewayRTL_433 + if (RFdata.containsKey("rssithreshold")) { + Log.notice(F("RTL_433 RSSI Threshold : %d " CR), RFConfig.rssiThreshold); + Config_update(RFdata, "rssithreshold", RFConfig.rssiThreshold); + rtl_433.setRSSIThreshold(RFConfig.rssiThreshold); + success = true; + } +# if defined(RF_SX1276) || defined(RF_SX1278) + if (RFdata.containsKey("ookthreshold")) { + Config_update(RFdata, "ookthreshold", RFConfig.newOokThreshold); + Log.notice(F("RTL_433 ookThreshold %d" CR), RFConfig.newOokThreshold); + rtl_433.setOOKThreshold(RFConfig.newOokThreshold); + success = true; + } +# endif + if (RFdata.containsKey("status")) { + Log.notice(F("RF get status:" CR)); + rtl_433.getStatus(); + success = true; + } + if (!success) { + Log.error(F("MQTTtoRF Fail json" CR)); + } +# endif + disableCurrentReceiver(); + enableActiveReceiver(); +# ifdef ESP32 + if (RFdata.containsKey("erase") && RFdata["erase"].as()) { + // Erase config from NVS (non-volatile storage) + preferences.begin(Gateway_Short_Name, false); + if (preferences.isKey("RFConfig")) { + int result = preferences.remove("RFConfig"); + Log.notice(F("RF config erase result: %d" CR), result); + preferences.end(); + return; // Erase prevails on save, so skipping save + } else { + Log.notice(F("RF config not found" CR)); + preferences.end(); + } + } + if (RFdata.containsKey("save") && RFdata["save"].as()) { + StaticJsonDocument jsonBuffer; + JsonObject jo = jsonBuffer.to(); + jo["frequency"] = RFConfig.frequency; + jo["active"] = RFConfig.activeReceiver; +// Don't save those for now, need to be tested +# ifdef ZgatewayRTL_433 +//jo["rssithreshold"] = RFConfig.rssiThreshold; +//jo["ookthreshold"] = RFConfig.newOokThreshold; +# endif + // Save config into NVS (non-volatile storage) + String conf = ""; + serializeJson(jsonBuffer, conf); + preferences.begin(Gateway_Short_Name, false); + int result = preferences.putString("RFConfig", conf); + preferences.end(); + Log.notice(F("RF Config_save: %s, result: %d" CR), conf.c_str(), result); + } +# endif +} + +void RFConfig_init() { + RFConfig.frequency = RF_FREQUENCY; + RFConfig.activeReceiver = ACTIVE_RECEIVER; + RFConfig.rssiThreshold = 0; + RFConfig.newOokThreshold = 0; +} + +void RFConfig_load() { +# ifdef ESP32 + StaticJsonDocument jsonBuffer; + preferences.begin(Gateway_Short_Name, true); + if (preferences.isKey("RFConfig")) { + auto error = deserializeJson(jsonBuffer, preferences.getString("RFConfig", "{}")); + preferences.end(); + if (error) { + Log.error(F("RF Config deserialization failed: %s, buffer capacity: %u" CR), error.c_str(), jsonBuffer.capacity()); + return; + } + if (jsonBuffer.isNull()) { + Log.warning(F("RF Config is null" CR)); + return; + } + JsonObject jo = jsonBuffer.as(); + RFConfig_fromJson(jo); + Log.notice(F("RF Config loaded" CR)); + } else { + preferences.end(); + Log.notice(F("RF Config not found using default" CR)); + enableActiveReceiver(); + } +# else + enableActiveReceiver(); +# endif +} + +void MQTTtoRFset(char* topicOri, JsonObject& RFdata) { + if (cmpToMainTopic(topicOri, subjectMQTTtoRFset)) { + Log.trace(F("MQTTtoRF json set" CR)); + + /* + * Configuration modifications priorities: + * First `init=true` and `load=true` commands are executed (if both are present, INIT prevails on LOAD) + * Then parameters included in json are taken in account + * Finally `erase=true` and `save=true` commands are executed (if both are present, ERASE prevails on SAVE) + */ + if (RFdata.containsKey("init") && RFdata["init"].as()) { + // Restore the default (initial) configuration + RFConfig_init(); + } else if (RFdata.containsKey("load") && RFdata["load"].as()) { + // Load the saved configuration, if not initialised + RFConfig_load(); + } + + // Load config from json if available + RFConfig_fromJson(RFdata); + stateRFMeasures(); + } +} +# else +void RFConfig_init() {} +void RFConfig_load() {} +void MQTTtoRFset(char* topicOri, JsonObject& RFdata) {} +void enableActiveReceiver() {} +# endif +#endif diff --git a/main/ZgatewayPilight.ino b/main/ZgatewayPilight.ino index 4e5c2abb6e..6d9539584a 100644 --- a/main/ZgatewayPilight.ino +++ b/main/ZgatewayPilight.ino @@ -112,21 +112,6 @@ void pilightRawCallback(const uint16_t* pulses, size_t length) { } # endif -void setupPilight() { -# ifdef ZradioCC1101 //receiving with CC1101 - ELECHOUSE_cc1101.Init(); - ELECHOUSE_cc1101.setMHZ(CC1101_FREQUENCY); - ELECHOUSE_cc1101.SetRx(CC1101_FREQUENCY); -# endif - rf.setCallback(pilightCallback); - rf.initReceiver(RF_RECEIVER_GPIO); - pinMode(RF_EMITTER_GPIO, OUTPUT); // Set this here, because if this is the RX pin it was reset to INPUT by Serial.end(); - Log.notice(F("RF_EMITTER_GPIO: %d " CR), RF_EMITTER_GPIO); - Log.notice(F("RF_RECEIVER_GPIO: %d " CR), RF_RECEIVER_GPIO); - Log.trace(F("ZgatewayPilight command topic: %s%s%s" CR), mqtt_topic, gateway_name, subjectMQTTtoPilight); - Log.trace(F("ZgatewayPilight setup done " CR)); -} - void savePilightConfig() { Log.trace(F("saving Pilight config" CR)); DynamicJsonDocument json(4096); @@ -231,13 +216,10 @@ void MQTTtoPilight(char* topicOri, JsonObject& Pilightdata) { } int msgLength = rf.stringToPulseTrain(raw, codes, MAXPULSESTREAMLENGTH); if (msgLength > 0) { -# ifdef ZradioCC1101 - disableActiveReceiver(); - ELECHOUSE_cc1101.Init(); + disableCurrentReceiver(); + initCC1101(); pinMode(RF_EMITTER_GPIO, OUTPUT); - ELECHOUSE_cc1101.SetTx(receiveMhz); // set Transmit on rf.disableReceiver(); -# endif rf.sendPulseTrain(codes, msgLength, repeats); Log.notice(F("MQTTtoPilight raw ok" CR)); success = true; @@ -262,13 +244,10 @@ void MQTTtoPilight(char* topicOri, JsonObject& Pilightdata) { } if (message && protocol) { Log.trace(F("MQTTtoPilight msg & protocol ok" CR)); -# ifdef ZradioCC1101 - disableActiveReceiver(); - ELECHOUSE_cc1101.Init(); + disableCurrentReceiver(); + initCC1101(); pinMode(RF_EMITTER_GPIO, OUTPUT); - ELECHOUSE_cc1101.SetTx(receiveMhz); // set Transmit on rf.disableReceiver(); -# endif int msgLength = rf.send(protocol, message); if (msgLength > 0) { Log.trace(F("Adv data MQTTtoPilight push state via PilighttoMQTT" CR)); @@ -294,18 +273,6 @@ void MQTTtoPilight(char* topicOri, JsonObject& Pilightdata) { } } } - if (Pilightdata.containsKey("active")) { - Log.trace(F("PiLight active:" CR)); - activeReceiver = ACTIVE_PILIGHT; // Enable PILIGHT gateway - success = true; - } -# ifdef ZradioCC1101 - if (Pilightdata.containsKey("mhz") && validFrequency(tempMhz)) { - receiveMhz = tempMhz; - Log.notice(F("PiLight Receive mhz: %F" CR), receiveMhz); - success = true; - } -# endif if (success) { // we acknowledge the sending by publishing the value to an acknowledgement topic, for the moment even if it is a signal repetition we acknowledge also pub(subjectGTWPilighttoMQTT, Pilightdata); @@ -313,7 +280,7 @@ void MQTTtoPilight(char* topicOri, JsonObject& Pilightdata) { pub(subjectGTWPilighttoMQTT, "{\"Status\": \"Error\"}"); // Fail feedback Log.error(F("MQTTtoPilight Fail json" CR)); } - enableActiveReceiver(false); + enableActiveReceiver(); } } @@ -324,25 +291,13 @@ extern void disablePilightReceive() { }; extern void enablePilightReceive() { -# ifdef ZradioCC1101 - Log.notice(F("Switching to Pilight Receiver: %F" CR), receiveMhz); -# else - Log.notice(F("Switching to Pilight Receiver" CR)); -# endif -# ifdef ZgatewayRF - disableRFReceive(); -# endif -# ifdef ZgatewayRF2 - disableRF2Receive(); -# endif -# ifdef ZgatewayRTL_433 - disableRTLreceive(); -# endif + Log.notice(F("Switching to Pilight Receiver: %F" CR), RFConfig.frequency); + Log.notice(F("RF_EMITTER_GPIO: %d " CR), RF_EMITTER_GPIO); + Log.notice(F("RF_RECEIVER_GPIO: %d " CR), RF_RECEIVER_GPIO); + Log.trace(F("ZgatewayPilight command topic: %s%s%s" CR), mqtt_topic, gateway_name, subjectMQTTtoPilight); + + initCC1101(); -# ifdef ZradioCC1101 - ELECHOUSE_cc1101.Init(); - ELECHOUSE_cc1101.SetRx(receiveMhz); // set Receive on -# endif rf.setCallback(pilightCallback); # ifdef Pilight_rawEnabled if (pilightRawEnabled) { @@ -353,5 +308,6 @@ extern void enablePilightReceive() { pinMode(RF_EMITTER_GPIO, OUTPUT); // Set this here, because if this is the RX pin it was reset to INPUT by Serial.end(); rf.enableReceiver(); loadPilightConfig(); + Log.trace(F("ZgatewayPilight setup done " CR)); }; #endif diff --git a/main/ZgatewayRF.ino b/main/ZgatewayRF.ino index d6b9937322..f0220da9b8 100644 --- a/main/ZgatewayRF.ino +++ b/main/ZgatewayRF.ino @@ -106,31 +106,6 @@ void RFtoMQTTdiscovery(SIGNAL_SIZE_UL_ULL MQTTvalue) { } # endif -void setupRF() { - //RF init parameters - Log.notice(F("RF_EMITTER_GPIO: %d " CR), RF_EMITTER_GPIO); - Log.notice(F("RF_RECEIVER_GPIO: %d " CR), RF_RECEIVER_GPIO); -# ifdef ZradioCC1101 //receiving with CC1101 - if (ELECHOUSE_cc1101.getCC1101()) { - Log.notice(F("C1101 spi Connection OK" CR)); - } else { - Log.error(F("C1101 spi Connection Error" CR)); - } - - ELECHOUSE_cc1101.Init(); - ELECHOUSE_cc1101.SetRx(receiveMhz); -# endif -# ifdef RF_DISABLE_TRANSMIT - mySwitch.disableTransmit(); -# else - mySwitch.enableTransmit(RF_EMITTER_GPIO); -# endif - mySwitch.setRepeatTransmit(RF_EMITTER_REPEAT); - mySwitch.enableReceive(RF_RECEIVER_GPIO); - Log.trace(F("ZgatewayRF command topic: %s%s%s" CR), mqtt_topic, gateway_name, subjectMQTTtoRF); - Log.trace(F("ZgatewayRF setup done" CR)); -} - void RFtoMQTT() { if (mySwitch.available()) { StaticJsonDocument RFdataBuffer; @@ -161,7 +136,7 @@ void RFtoMQTT() { RFdata["raw"] = rawDump; # endif # ifdef ZradioCC1101 // set Receive off and Transmitt on - RFdata["mhz"] = receiveMhz; + RFdata["frequency"] = RFConfig.frequency; # endif mySwitch.resetAvailable(); @@ -187,9 +162,9 @@ void RFtoMQTT() { # if simpleReceiving void MQTTtoRF(char* topicOri, char* datacallback) { # ifdef ZradioCC1101 // set Receive off and Transmitt on - disableActiveReceiver(); - ELECHOUSE_cc1101.SetTx(receiveMhz); - Log.notice(F("Transmit mhz: %F" CR), receiveMhz); + disableCurrentReceiver(); + ELECHOUSE_cc1101.SetTx(RFConfig.frequency); + Log.notice(F("Transmit mhz: %F" CR), RFConfig.frequency); # endif mySwitch.disableReceive(); mySwitch.enableTransmit(RF_EMITTER_GPIO); @@ -241,7 +216,7 @@ void MQTTtoRF(char* topicOri, char* datacallback) { pub(subjectGTWRFtoMQTT, datacallback); // we acknowledge the sending by publishing the value to an acknowledgement topic, for the moment even if it is a signal repetition we acknowledge also } # ifdef ZradioCC1101 // set Receive on and Transmitt off - ELECHOUSE_cc1101.SetRx(receiveMhz); + ELECHOUSE_cc1101.SetRx(RFConfig.frequency); mySwitch.disableTransmit(); mySwitch.enableReceive(RF_RECEIVER_GPIO); # endif @@ -262,13 +237,13 @@ void MQTTtoRF(char* topicOri, JsonObject& RFdata) { // json object decoding Log.notice(F("RF Pulse Lgth: %d" CR), valuePLSL); Log.notice(F("Bits nb: %d" CR), valueBITS); # ifdef ZradioCC1101 // set Receive off and Transmitt on - disableActiveReceiver(); + disableCurrentReceiver(); int txPower = RFdata["txpower"] | RF_CC1101_TXPOWER; ELECHOUSE_cc1101.setPA((int)txPower); Log.notice(F("CC1101 TX Power: %d" CR), txPower); - float trMhz = RFdata["mhz"] | CC1101_FREQUENCY; + float trMhz = RFdata["mhz"] | RF_FREQUENCY; if (validFrequency((int)trMhz)) { ELECHOUSE_cc1101.SetTx(trMhz); Log.notice(F("Transmit mhz: %F" CR), trMhz); @@ -283,32 +258,9 @@ void MQTTtoRF(char* topicOri, JsonObject& RFdata) { // json object decoding // we acknowledge the sending by publishing the value to an acknowledgement topic, for the moment even if it is a signal repetition we acknowledge also pub(subjectGTWRFtoMQTT, RFdata); mySwitch.setRepeatTransmit(RF_EMITTER_REPEAT); // Restore the default value - } else { - bool success = false; - if (RFdata.containsKey("active")) { - Log.trace(F("RF active:" CR)); - activeReceiver = ACTIVE_RF; - success = true; - } -# ifdef ZradioCC1101 // set Receive on and Transmitt off - float tempMhz = RFdata["mhz"]; - if (RFdata.containsKey("mhz") && validFrequency(tempMhz)) { - receiveMhz = tempMhz; - Log.notice(F("Receive mhz: %F" CR), receiveMhz); - success = true; - } -# endif - if (success) { - // we acknowledge the sending by publishing the value to an acknowledgement topic, for the moment even if it is a signal repetition we acknowledge also - pub(subjectGTWRFtoMQTT, RFdata); - } else { -# ifndef ARDUINO_AVR_UNO // Space issues with the UNO - pub(subjectGTWRFtoMQTT, "{\"Status\": \"Error\"}"); // Fail feedback -# endif - Log.error(F("MQTTtoRF Fail json" CR)); - } } - enableActiveReceiver(false); + + enableActiveReceiver(); } } # endif @@ -317,36 +269,24 @@ int receiveInterupt = -1; void disableRFReceive() { Log.trace(F("disableRFReceive %d" CR), receiveInterupt); - if (receiveInterupt != -1) { - receiveInterupt = -1; - mySwitch.disableReceive(); - } + mySwitch.disableReceive(); } void enableRFReceive() { -# ifdef ZradioCC1101 - Log.notice(F("Switching to RF Receiver: %F" CR), receiveMhz); -# else - Log.notice(F("Switching to RF Receiver" CR)); -# endif -# ifndef ARDUINO_AVR_UNO // Space issues with the UNO -# ifdef ZgatewayPilight - disablePilightReceive(); -# endif -# ifdef ZgatewayRTL_433 - disableRTLreceive(); -# endif -# endif -# ifdef ZgatewayRF2 - disableRF2Receive(); -# endif + Log.notice(F("Enable RF Receiver: %FMhz" CR), RFConfig.frequency); + //RF init parameters + Log.notice(F("RF_EMITTER_GPIO: %d " CR), RF_EMITTER_GPIO); + Log.notice(F("RF_RECEIVER_GPIO: %d " CR), RF_RECEIVER_GPIO); -# ifdef ZradioCC1101 // set Receive on and Transmitt off - ELECHOUSE_cc1101.Init(); - ELECHOUSE_cc1101.SetRx(receiveMhz); -# endif +# ifdef RF_DISABLE_TRANSMIT mySwitch.disableTransmit(); +# else + mySwitch.enableTransmit(RF_EMITTER_GPIO); +# endif receiveInterupt = RF_RECEIVER_GPIO; - mySwitch.enableReceive(RF_RECEIVER_GPIO); + mySwitch.setRepeatTransmit(RF_EMITTER_REPEAT); + mySwitch.enableReceive(receiveInterupt); + Log.trace(F("ZgatewayRF command topic: %s%s%s" CR), mqtt_topic, gateway_name, subjectMQTTtoRF); + Log.trace(F("ZgatewayRF setup done" CR)); } #endif diff --git a/main/ZgatewayRF2.ino b/main/ZgatewayRF2.ino index 76c41871a5..843c38b9d1 100644 --- a/main/ZgatewayRF2.ino +++ b/main/ZgatewayRF2.ino @@ -55,21 +55,6 @@ struct RF2rxd { RF2rxd rf2rd; -void setupRF2() { -# ifdef ZradioCC1101 //receiving with CC1101 - ELECHOUSE_cc1101.Init(); - ELECHOUSE_cc1101.setMHZ(receiveMhz); - ELECHOUSE_cc1101.SetRx(receiveMhz); -# endif - NewRemoteReceiver::init(RF_RECEIVER_GPIO, 2, rf2Callback); - Log.notice(F("RF_EMITTER_GPIO: %d " CR), RF_EMITTER_GPIO); - Log.notice(F("RF_RECEIVER_GPIO: %d " CR), RF_RECEIVER_GPIO); - Log.trace(F("ZgatewayRF2 command topic: %s%s%s" CR), mqtt_topic, gateway_name, subjectMQTTtoRF2); - Log.trace(F("ZgatewayRF2 setup done " CR)); - pinMode(RF_EMITTER_GPIO, OUTPUT); - digitalWrite(RF_EMITTER_GPIO, LOW); -} - # ifdef ZmqttDiscovery //Register for autodiscover in Home Assistant void RF2toMQTTdiscovery(JsonObject& data) { @@ -148,13 +133,9 @@ void rf2Callback(unsigned int period, unsigned long address, unsigned long group # if simpleReceiving void MQTTtoRF2(char* topicOri, char* datacallback) { -# ifdef ZradioCC1101 NewRemoteReceiver::disable(); - disableActiveReceiver(); - ELECHOUSE_cc1101.Init(); pinMode(RF_EMITTER_GPIO, OUTPUT); - ELECHOUSE_cc1101.SetTx(CC1101_FREQUENCY); // set Transmit on -# endif + initCC1101(); // RF DATA ANALYSIS //We look into the subject to see if a special RF protocol is defined @@ -253,7 +234,7 @@ void MQTTtoRF2(char* topicOri, char* datacallback) { } } # ifdef ZradioCC1101 - ELECHOUSE_cc1101.SetRx(receiveMhz); // set Receive on + ELECHOUSE_cc1101.SetRx(RFConfig.frequency); // set Receive on NewRemoteReceiver::enable(); # endif } @@ -267,13 +248,9 @@ void MQTTtoRF2(char* topicOri, JsonObject& RF2data) { // json object decoding int boolSWITCHTYPE = RF2data["switchType"] | 99; bool success = false; if (boolSWITCHTYPE != 99) { -# ifdef ZradioCC1101 NewRemoteReceiver::disable(); - disableActiveReceiver(); - ELECHOUSE_cc1101.Init(); pinMode(RF_EMITTER_GPIO, OUTPUT); - ELECHOUSE_cc1101.SetTx(CC1101_FREQUENCY); // set Transmit on -# endif + initCC1101(); Log.trace(F("MQTTtoRF2 switch type ok" CR)); bool isDimCommand = boolSWITCHTYPE == 2; unsigned long valueCODE = RF2data["address"]; @@ -311,19 +288,6 @@ void MQTTtoRF2(char* topicOri, JsonObject& RF2data) { // json object decoding success = true; } } - if (RF2data.containsKey("active")) { - Log.trace(F("RF2 active:" CR)); - activeReceiver = ACTIVE_RF2; - success = true; - } -# ifdef ZradioCC1101 // set Receive on and Transmitt off - float tempMhz = RF2data["mhz"]; - if (RF2data.containsKey("mhz") && validFrequency(tempMhz)) { - receiveMhz = tempMhz; - Log.notice(F("Receive mhz: %F" CR), receiveMhz); - success = true; - } -# endif if (success) { // we acknowledge the sending by publishing the value to an acknowledgement topic, for the moment even if it is a signal repetition we acknowledge also pub(subjectRF2toMQTT, RF2data); @@ -333,39 +297,26 @@ void MQTTtoRF2(char* topicOri, JsonObject& RF2data) { // json object decoding # endif Log.error(F("MQTTtoRF2 failed json read" CR)); } - enableActiveReceiver(false); + enableActiveReceiver(); } } # endif void disableRF2Receive() { Log.trace(F("disableRF2Receive" CR)); - NewRemoteReceiver::deinit(); - NewRemoteReceiver::init(-1, 2, rf2Callback); // mark _interupt with -1 - NewRemoteReceiver::deinit(); + NewRemoteReceiver::disable(); } void enableRF2Receive() { -# ifdef ZradioCC1101 - Log.notice(F("Switching to RF2 Receiver: %F" CR), receiveMhz); -# else - Log.notice(F("Switching to RF2 Receiver" CR)); -# endif -# ifdef ZgatewayPilight - disablePilightReceive(); -# endif -# ifdef ZgatewayRTL_433 - disableRTLreceive(); -# endif -# ifdef ZgatewayRF - disableRFReceive(); -# endif - -# ifdef ZradioCC1101 - ELECHOUSE_cc1101.Init(); - ELECHOUSE_cc1101.SetRx(receiveMhz); // set Receive on -# endif + Log.trace(F("enableRF2Receive" CR)); NewRemoteReceiver::init(RF_RECEIVER_GPIO, 2, rf2Callback); + + Log.notice(F("RF_EMITTER_GPIO: %d " CR), RF_EMITTER_GPIO); + Log.notice(F("RF_RECEIVER_GPIO: %d " CR), RF_RECEIVER_GPIO); + Log.trace(F("ZgatewayRF2 command topic: %s%s%s" CR), mqtt_topic, gateway_name, subjectMQTTtoRF2); + pinMode(RF_EMITTER_GPIO, OUTPUT); + digitalWrite(RF_EMITTER_GPIO, LOW); + Log.trace(F("ZgatewayRF2 setup done " CR)); } #endif diff --git a/main/ZgatewayRTL_433.ino b/main/ZgatewayRTL_433.ino index 73902c1f11..1f0c38c55b 100644 --- a/main/ZgatewayRTL_433.ino +++ b/main/ZgatewayRTL_433.ino @@ -40,8 +40,6 @@ char messageBuffer[JSON_MSG_BUFFER]; -rtl_433_ESP rtl_433; - # ifdef ZmqttDiscovery SemaphoreHandle_t semaphorecreateOrUpdateDeviceRTL_433; std::vector RTL_433devices; @@ -273,7 +271,7 @@ void setupRTL_433() { semaphorecreateOrUpdateDeviceRTL_433 = xSemaphoreCreateBinary(); xSemaphoreGive(semaphorecreateOrUpdateDeviceRTL_433); # endif - Log.trace(F("ZgatewayRTL_433 command topic: %s%s%s" CR), mqtt_topic, gateway_name, subjectMQTTtoRTL_433); + Log.trace(F("ZgatewayRTL_433 command topic: %s%s%s" CR), mqtt_topic, gateway_name, subjectMQTTtoRFset); Log.notice(F("ZgatewayRTL_433 setup done " CR)); } @@ -281,69 +279,9 @@ void RTL_433Loop() { rtl_433.loop(); } -extern void MQTTtoRTL_433(char* topicOri, JsonObject& RTLdata) { - if (cmpToMainTopic(topicOri, subjectMQTTtoRTL_433)) { - float tempMhz = RTLdata["mhz"]; - bool success = false; - if (RTLdata.containsKey("mhz") && validFrequency(tempMhz)) { - receiveMhz = tempMhz; - Log.notice(F("RTL_433 Receive mhz: %F" CR), receiveMhz); - success = true; - } - if (RTLdata.containsKey("active")) { - Log.trace(F("RTL_433 active:" CR)); - activeReceiver = ACTIVE_RTL; // Enable RTL_433 gateway - success = true; - } - if (RTLdata.containsKey("rssi")) { - int rssiThreshold = RTLdata["rssi"] | 0; - Log.notice(F("RTL_433 RSSI Threshold Delta: %d " CR), rssiThreshold); - rtl_433.setRSSIThreshold(rssiThreshold); - success = true; - } -# if defined(RF_SX1276) || defined(RF_SX1278) - if (RTLdata.containsKey("ookThreshold")) { - int newOokThreshold = RTLdata["ookThreshold"] | 0; - Log.notice(F("RTL_433 ookThreshold %d" CR), newOokThreshold); - rtl_433.setOOKThreshold(newOokThreshold); - success = true; - } -# endif - if (RTLdata.containsKey("debug")) { - int debug = RTLdata["debug"] | -1; - Log.notice(F("RTL_433 set debug: %d" CR), debug); - // rtl_433.setDebug(debug); - rtl_433.initReceiver(RF_MODULE_RECEIVER_GPIO, receiveMhz); - success = true; - } - if (RTLdata.containsKey("status")) { - Log.notice(F("RTL_433 get status:" CR)); - rtl_433.getStatus(); - success = true; - } - if (success) { - pub(subjectRTL_433toMQTT, RTLdata); - } else { - pub(subjectRTL_433toMQTT, "{\"Status\": \"Error\"}"); // Fail feedback - Log.error(F("[rtl_433] MQTTtoRTL_433 Fail json" CR)); - } - enableActiveReceiver(false); - } -} - extern void enableRTLreceive() { - Log.notice(F("Switching to RTL_433 Receiver: %FMhz" CR), receiveMhz); -# ifdef ZgatewayRF - disableRFReceive(); -# endif -# ifdef ZgatewayRF2 - disableRF2Receive(); -# endif -# ifdef ZgatewayPilight - disablePilightReceive(); -# endif - - rtl_433.initReceiver(RF_MODULE_RECEIVER_GPIO, receiveMhz); + Log.notice(F("Enable RTL_433 Receiver: %FMhz" CR), RFConfig.frequency); + rtl_433.initReceiver(RF_MODULE_RECEIVER_GPIO, RFConfig.frequency); rtl_433.enableReceiver(); } diff --git a/main/ZwebUI.ino b/main/ZwebUI.ino index 4da4402ffe..71f3e3d6b2 100644 --- a/main/ZwebUI.ino +++ b/main/ZwebUI.ino @@ -947,54 +947,72 @@ void handleLA() { if (server.hasArg("save")) { StaticJsonDocument jsonBuffer; JsonObject WEBtoLORA = jsonBuffer.to(); - + bool update = false; if (server.hasArg("lf")) { WEBtoLORA["frequency"] = server.arg("lf"); + update = true; } if (server.hasArg("lt")) { WEBtoLORA["txpower"] = server.arg("lt"); + update = true; } if (server.hasArg("ls")) { WEBtoLORA["spreadingfactor"] = server.arg("ls"); + update = true; } if (server.hasArg("lb")) { WEBtoLORA["signalbandwidth"] = server.arg("lb"); + update = true; } if (server.hasArg("lc")) { WEBtoLORA["codingrate"] = server.arg("lc"); + update = true; } if (server.hasArg("ll")) { WEBtoLORA["preamblelength"] = server.arg("ll"); + update = true; } if (server.hasArg("lw")) { WEBtoLORA["syncword"] = server.arg("lw"); + update = true; } if (server.hasArg("lr")) { WEBtoLORA["enablecrc"] = server.arg("lr"); + update = true; } else { WEBtoLORA["enablecrc"] = false; + update = true; } if (server.hasArg("li")) { WEBtoLORA["invertiq"] = server.arg("li"); + update = true; } else { WEBtoLORA["invertiq"] = false; + update = true; } if (server.hasArg("ok")) { WEBtoLORA["onlyknown"] = server.arg("ok"); + update = true; } else { WEBtoLORA["onlyknown"] = false; + update = true; + } + if (update) { + Log.notice(F("[WebUI] Save data" CR)); + WEBtoLORA["save"] = true; + LORAConfig_fromJson(WEBtoLORA); + stateLORAMeasures(); + Log.trace(F("[WebUI] LORAConfig end" CR)); } - - LORAConfig_fromJson(WEBtoLORA); } } char jsonChar[100]; @@ -1056,8 +1074,121 @@ void handleLA() { snprintf(buffer, WEB_TEMPLATE_BUFFER_MAX_SIZE, footer, OMG_VERSION); response += String(buffer); server.send(200, "text/html", response); - stateLORAMeasures(); - Log.trace(F("[WebUI] LORAConfig end" CR)); +} +# elif defined(ZgatewayRTL_433) || defined(ZgatewayPiLight) || defined(ZgatewayRF) || defined(ZgatewayRF2) || defined(ZactuatorSomfy) +# include +std::map activeReceiverOptions = { + {0, "Inactive"}, +# if defined(ZgatewayPiLight) && !defined(ZradioSX127x) + {1, "PiLight"}, +# endif +# if defined(ZgatewayRF) && !defined(ZradioSX127x) + {2, "RF"}, +# endif +# ifdef ZgatewayRTL_433 + {3, "RTL_433"}, +# endif +# if defined(ZgatewayRF2) && !defined(ZradioSX127x) + {4, "RF2 (restart required)"} +# endif +}; + +bool isValidReceiver(int receiverId) { + // Check if the receiverId exists in the activeReceiverOptions map + return activeReceiverOptions.find(receiverId) != activeReceiverOptions.end(); +} + +String generateActiveReceiverOptions(int currentSelection) { + String optionsHtml = ""; + for (const auto& option : activeReceiverOptions) { + optionsHtml += "