Initial commit

This commit is contained in:
Robert Strouse 2023-01-09 18:15:30 -08:00
commit ee367e7111
28 changed files with 53359 additions and 0 deletions

2
.gitattributes vendored Normal file
View file

@ -0,0 +1,2 @@
# Auto detect text files and perform LF normalization
* text=auto

8
.theia/launch.json Normal file
View file

@ -0,0 +1,8 @@
{
// Use IntelliSense to learn about possible attributes.
// Hover to view descriptions of existing attributes.
"version": "0.2.0",
"configurations": [
]
}

266
ConfigSettings.cpp Normal file
View file

@ -0,0 +1,266 @@
#include <Arduino.h>
#include <LittleFS.h> // https://github.com/espressif/arduino-esp32/tree/master/libraries/LittleFS
#include <time.h>
#include <WiFi.h>
#include <Preferences.h>
#include "ConfigSettings.h"
Preferences pref;
bool BaseSettings::load() { return true; }
bool BaseSettings::save() { return true; }
bool BaseSettings::loadFile(const char *filename) {
size_t filesize = 10;
String data = "";
if(LittleFS.exists(filename)) {
File file = LittleFS.open(filename, "r");
filesize += file.size();
while(file.available()) {
char c = file.read();
data += c;
}
DynamicJsonDocument doc(filesize);
DeserializationError err = deserializeJson(doc, data);
JsonObject obj = doc.as<JsonObject>();
this->fromJSON(obj);
file.close();
}
return false;
}
bool BaseSettings::saveFile(const char *filename) {
File file = LittleFS.open(filename, "w");
DynamicJsonDocument doc(2048);
JsonObject obj = doc.as<JsonObject>();
this->toJSON(obj);
serializeJson(doc, file);
file.close();
}
bool BaseSettings::parseValueString(JsonObject &obj, const char *prop, char *pdest, size_t size) {
if(obj.containsKey(prop)) strlcpy(pdest, obj[prop], size);
return true;
}
int BaseSettings::parseValueInt(JsonObject &obj, const char *prop, int defVal) {
if(obj.containsKey(prop)) return obj[prop];
return defVal;
}
double BaseSettings::parseValueDouble(JsonObject &obj, const char *prop, double defVal) {
if(obj.containsKey(prop)) return obj[prop];
return defVal;
}
bool ConfigSettings::begin() {
this->WIFI.begin();
this->NTP.begin();
this->MQTT.begin();
this->print();
return true;
}
void ConfigSettings::print() {
this->NTP.print();
this->WIFI.print();
}
void ConfigSettings::emitSockets() {
}
bool MQTTSettings::begin() {
this->load();
return true;
}
bool MQTTSettings::toJSON(JsonObject &obj) {
obj["enabled"] = this->enabled;
obj["protocol"] = this->protocol;
obj["hostname"] = this->hostname;
obj["port"] = this->port;
obj["username"] = this->username;
obj["password"] = this->password;
obj["rootTopic"] = this->rootTopic;
return true;
}
bool MQTTSettings::fromJSON(JsonObject &obj) {
if(obj.containsKey("enabled")) this->enabled = obj["enabled"];
this->parseValueString(obj, "protocol", this->protocol, sizeof(this->protocol));
this->parseValueString(obj, "hostname", this->hostname, sizeof(this->hostname));
this->parseValueString(obj, "username", this->username, sizeof(this->username));
this->parseValueString(obj, "password", this->password, sizeof(this->password));
this->parseValueString(obj, "rootTopic", this->rootTopic, sizeof(this->rootTopic));
return true;
}
bool MQTTSettings::save() {
pref.begin("MQTT");
pref.clear();
pref.putString("protocol", this->protocol);
pref.putString("hostname", this->hostname);
pref.putShort("port", this->port);
pref.putString("username", this->username);
pref.putString("password", this->password);
pref.putString("rootTopic", this->rootTopic);
pref.putBool("enabled", this->enabled);
pref.end();
return true;
}
bool MQTTSettings::load() {
pref.begin("MQTT");
pref.getString("protocol", this->protocol, sizeof(this->protocol));
pref.getString("hostname", this->hostname, sizeof(this->hostname));
this->port = pref.getShort("port", 1883);
pref.getString("username", this->username, sizeof(this->username));
pref.getString("password", this->password, sizeof(this->password));
pref.getString("rootTopic", this->rootTopic, sizeof(this->rootTopic));
this->enabled = pref.getBool("enabled", false);
pref.end();
return true;
}
bool ConfigSettings::toJSON(DynamicJsonDocument &doc) {
doc["fwVersion"] = this->fwVersion;
JsonObject objWIFI = doc.createNestedObject("WIFI");
this->WIFI.toJSON(objWIFI);
JsonObject objNTP = doc.createNestedObject("NTP");
this->NTP.toJSON(objNTP);
JsonObject objMQTT = doc.createNestedObject("MQTT");
this->MQTT.toJSON(objMQTT);
return true;
}
bool NTPSettings::begin() {
this->load();
this->apply();
return true;
}
bool NTPSettings::save() {
pref.begin("NTP");
pref.clear();
pref.putString("ntpServer", this->ntpServer);
pref.putString("posixZone", this->posixZone);
pref.end();
struct tm dt;
configTime(0, 0, this->ntpServer);
if(!getLocalTime(&dt)) return false;
setenv("TZ", this->posixZone, 1);
return true;
}
bool NTPSettings::load() {
pref.begin("NTP");
pref.getString("ntpServer", this->ntpServer, sizeof(this->ntpServer));
pref.getString("posixZone", this->posixZone, sizeof(this->posixZone));
pref.end();
return true;
}
void NTPSettings::print() {
Serial.println("NTP Settings ");
Serial.print(this->ntpServer);
Serial.print(" TZ:");
Serial.println(this->posixZone);
}
bool NTPSettings::fromJSON(JsonObject &obj) {
this->parseValueString(obj, "ntpServer", this->ntpServer, sizeof(this->ntpServer));
this->parseValueString(obj, "posixZone", this->posixZone, sizeof(this->posixZone));
return true;
}
bool NTPSettings::toJSON(JsonObject &obj) {
obj["ntpServer"] = this->ntpServer;
obj["posixZone"] = this->posixZone;
return true;
}
bool NTPSettings::apply() {
struct tm dt;
configTime(0, 0, this->ntpServer);
if(!getLocalTime(&dt)) return false;
setenv("TZ", this->posixZone, 1);
return true;
}
bool WifiSettings::begin() {
this->load();
return true;
}
bool WifiSettings::fromJSON(JsonObject &obj) {
this->parseValueString(obj, "hostname", this->hostname, sizeof(this->hostname));
this->parseValueString(obj, "ssid", this->ssid, sizeof(this->ssid));
this->parseValueString(obj, "passphrase", this->passphrase, sizeof(this->passphrase));
if(obj.containsKey("ssdpBroadcast")) this->ssdpBroadcast = obj["ssdpBroadcast"];
return true;
}
bool WifiSettings::toJSON(JsonObject &obj) {
obj["hostname"] = this->hostname;
obj["ssid"] = this->ssid;
obj["passphrase"] = this->passphrase;
obj["ssdpBroadcast"] = this->ssdpBroadcast;
return true;
}
bool WifiSettings::save() {
pref.begin("WIFI");
pref.clear();
pref.putString("hostname", this->hostname);
pref.putString("ssid", this->ssid);
pref.putString("passphrase", this->passphrase);
pref.putBool("ssdpBroadcast", this->ssdpBroadcast);
pref.end();
return true;
}
bool WifiSettings::load() {
pref.begin("WIFI");
pref.getString("hostname", this->hostname, sizeof(this->hostname));
pref.getString("ssid", this->ssid, sizeof(this->ssid));
pref.getString("passphrase", this->passphrase, sizeof(this->passphrase));
this->ssdpBroadcast = pref.getBool("ssdpBroadcast", true);
pref.end();
return true;
}
String WifiSettings::mapEncryptionType(int type) {
switch(type) {
case WIFI_AUTH_OPEN:
return "Open";
case WIFI_AUTH_WEP:
return "WEP";
case WIFI_AUTH_WPA_PSK:
return "WPA/PSK";
case WIFI_AUTH_WPA2_PSK:
return "WPA2/PSK";
case WIFI_AUTH_WPA_WPA2_PSK:
return "WPA/WPA2/PSK";
case WIFI_AUTH_WPA2_ENTERPRISE:
return "WPA/Enterprise";
return "Unknown";
}
}
void WifiSettings::print() {
Serial.println("WIFI Settings");
Serial.print("HOST: ");
Serial.print(this->hostname);
Serial.print(" SSID: [");
Serial.print(this->ssid);
Serial.print("] PassPhrase: [");
Serial.print(this->passphrase);
Serial.println("]");
}
void WifiSettings::printNetworks() {
int n = WiFi.scanNetworks(false, true);
Serial.print("Scanned ");
Serial.print(n);
Serial.println(" Networks...");
String network;
uint8_t encType;
int32_t RSSI;
uint8_t* BSSID;
int32_t channel;
bool isHidden;
for(int i = 0; i < n; i++) {
if(WiFi.SSID(i).compareTo(this->ssid) == 0) Serial.print("*");
else Serial.print(" ");
Serial.print(i);
Serial.print(": ");
Serial.print(WiFi.SSID(i));
Serial.print(" (");
Serial.print(WiFi.RSSI(i));
Serial.print("dBm) CH:");
Serial.print(WiFi.channel(i));
Serial.print(" MAC:");
Serial.print(WiFi.BSSIDstr(i));
if(isHidden) Serial.print(" [hidden]");
Serial.println();
}
}
bool WifiSettings::ssidExists(const char *ssid) {
int n = WiFi.scanNetworks(false, true);
for(int i = 0; i < n; i++) {
if(WiFi.SSID(i).compareTo(ssid) == 0) return true;
}
return false;
}

82
ConfigSettings.h Normal file
View file

@ -0,0 +1,82 @@
#include <ArduinoJson.h>
#ifndef configsettings_h
#define configsettings_h
#define FW_VERSION "v0.90.1"
enum DeviceStatus {
DS_OK = 0,
DS_ERROR = 1,
DS_FWUPDATE = 2
};
class BaseSettings {
public:
bool loadFile(const char* filename);
bool fromJSON(JsonObject &obj);
bool toJSON(JsonObject &obj);
bool parseValueString(JsonObject &obj, const char *prop, char *dest, size_t size);
int parseValueInt(JsonObject &obj, const char *prop, int defVal);
double parseValueDouble(JsonObject &obj, const char *prop, double defVal);
bool saveFile(const char* filename);
bool save();
bool load();
};
class NTPSettings: BaseSettings {
public:
char ntpServer[64] = "pool.ntp.org";
char posixZone[64] = "";
bool fromJSON(JsonObject &obj);
bool toJSON(JsonObject &obj);
bool apply();
bool begin();
bool save();
bool load();
void print();
};
class WifiSettings: BaseSettings {
public:
char hostname[32] = "";
char ssid[32] = "";
char passphrase[32] = "";
bool ssdpBroadcast = true;
bool begin();
bool fromJSON(JsonObject &obj);
bool toJSON(JsonObject &obj);
String mapEncryptionType(int type);
bool ssidExists(const char *ssid);
void printNetworks();
bool save();
bool load();
void print();
};
class MQTTSettings: BaseSettings {
public:
bool enabled = false;
char hostname[32] = "";
char protocol[10] = "mqtt://";
uint16_t port = 1883;
char username[32] = "";
char password[32] = "";
char rootTopic[64] = "";
bool begin();
bool save();
bool load();
bool toJSON(JsonObject &obj);
bool fromJSON(JsonObject &obj);
};
class ConfigSettings: BaseSettings {
public:
const char* fwVersion = FW_VERSION;
uint8_t status;
WifiSettings WIFI;
NTPSettings NTP;
MQTTSettings MQTT;
bool begin();
bool save();
bool load();
void print();
void emitSockets();
bool toJSON(DynamicJsonDocument &doc);
};
#endif

24
LICENSE Normal file
View file

@ -0,0 +1,24 @@
This is free and unencumbered software released into the public domain.
Anyone is free to copy, modify, publish, use, compile, sell, or
distribute this software, either in source code form or as a compiled
binary, for any purpose, commercial or non-commercial, and by any
means.
In jurisdictions that recognize copyright laws, the author or authors
of this software dedicate any and all copyright interest in the
software to the public domain. We make this dedication for the benefit
of the public at large and to the detriment of our heirs and
successors. We intend this dedication to be an overt act of
relinquishment in perpetuity of all present and future rights to this
software under copyright law.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.
IN NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY CLAIM, DAMAGES OR
OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR
OTHER DEALINGS IN THE SOFTWARE.
For more information, please refer to <https://unlicense.org>

106
MQTT.cpp Normal file
View file

@ -0,0 +1,106 @@
#include <WiFi.h>
#include <PubSubClient.h>
#include <ArduinoJson.h>
#include "MQTT.h"
#include "ConfigSettings.h"
#include "Somfy.h"
WiFiClient tcpClient;
PubSubClient mqttClient(tcpClient);
#define MQTT_MAX_RESPONSE 2048
static char g_content[MQTT_MAX_RESPONSE];
extern ConfigSettings settings;
extern SomfyShadeController somfy;
bool MQTTClass::begin() {
return true;
}
bool MQTTClass::end() {
this->disconnect();
return true;
}
bool MQTTClass::loop() {
if(settings.MQTT.enabled && !mqttClient.connected())
this->connect();
mqttClient.loop();
return true;
}
bool MQTTClass::connect() {
if(mqttClient.connected()) {
if(!settings.MQTT.enabled)
return this->disconnect();
else
return true;
}
if(settings.MQTT.enabled) {
uint64_t mac = ESP.getEfuseMac();
snprintf(this->clientId, sizeof(this->clientId), "client-%08lx%08lx", (uint32_t)((mac >> 32) & 0xFFFFFFFF), (uint32_t)(mac & 0xFFFFFFFF));
if(strlen(settings.MQTT.protocol) > 0 && strlen(settings.MQTT.hostname) > 0) {
mqttClient.setServer(settings.MQTT.hostname, settings.MQTT.port);
if(mqttClient.connect(this->clientId, settings.MQTT.username, settings.MQTT.password)) {
Serial.print("Successfully connected MQTT client ");
Serial.println(this->clientId);
somfy.publish();
return true;
}
else {
Serial.print("MQTT Connection failed for ");
Serial.println(mqttClient.state());
}
}
else
return true;
}
return true;
}
bool MQTTClass::disconnect() {
if(mqttClient.connected()) {
mqttClient.disconnect();
}
return true;
}
bool MQTTClass::publish(const char *topic, const char *payload) {
if(mqttClient.connected()) {
char top[64];
if(strlen(settings.MQTT.rootTopic) > 0)
snprintf(top, sizeof(top), "%s/%s", settings.MQTT.rootTopic, topic);
else
strlcpy(top, topic, sizeof(top));
mqttClient.publish(top, payload);
return true;
}
return false;
}
bool MQTTClass::publish(const char *topic, uint32_t val) {
snprintf(g_content, sizeof(g_content), "%u", val);
return this->publish(topic, g_content);
}
bool MQTTClass::publish(const char *topic, JsonDocument &doc) {
serializeJson(doc, g_content, sizeof(g_content));
return this->publish(topic, g_content);
}
bool MQTTClass::publish(const char *topic, JsonArray &arr) {
serializeJson(arr, g_content, sizeof(g_content));
return this->publish(topic, g_content);
}
bool MQTTClass::publish(const char *topic, JsonObject &obj) {
serializeJson(obj, g_content, sizeof(g_content));
return this->publish(topic, g_content);
}
bool MQTTClass::publish(const char *topic, int8_t val) {
snprintf(g_content, sizeof(g_content), "%d", val);
return this->publish(topic, g_content);
}
bool MQTTClass::publish(const char *topic, uint8_t val) {
snprintf(g_content, sizeof(g_content), "%u", val);
return this->publish(topic, g_content);
}
bool MQTTClass::publish(const char *topic, uint16_t val) {
snprintf(g_content, sizeof(g_content), "%u", val);
return this->publish(topic, g_content);
}
bool MQTTClass::connected() {
if(settings.MQTT.enabled) return mqttClient.connected();
return false;
}

25
MQTT.h Normal file
View file

@ -0,0 +1,25 @@
#ifndef MQTT_H
#define MQTT_H
#include <Arduino.h>
#include <PubSubClient.h>
#include <ArduinoJson.h>
class MQTTClass {
public:
char clientId[32] = {'\0'};
bool begin();
bool loop();
bool end();
bool connect();
bool disconnect();
bool connected();
bool publish(const char *topic, const char *payload);
bool publish(const char *topic, JsonDocument &doc);
bool publish(const char *topic, JsonArray &arr);
bool publish(const char *topic, JsonObject &obj);
bool publish(const char *topic, uint8_t val);
bool publish(const char *topic, int8_t val);
bool publish(const char *topic, uint32_t val);
bool publish(const char *topic, uint16_t val);
};
#endif

287
Network.cpp Normal file
View file

@ -0,0 +1,287 @@
#include <Arduino.h>
#include <WiFi.h>
#include <ESPmDNS.h>
#include "ConfigSettings.h"
#include "Network.h"
#include "Web.h"
#include "Sockets.h"
#include "Utils.h"
#include "SSDP.h"
#include "MQTT.h"
extern ConfigSettings settings;
extern Web webServer;
extern SocketEmitter sockEmit;
extern MQTTClass mqtt;
void Network::end() {
sockEmit.end();
SSDP.end();
mqtt.end();
delay(100);
}
bool Network::setup() {
WiFi.persistent(false);
Serial.print("WiFi Mode: ");
Serial.println(WiFi.getMode());
if(WiFi.status() == WL_CONNECTED) WiFi.disconnect(true);
WiFi.mode(WIFI_AP_STA);
settings.WIFI.printNetworks();
sockEmit.begin();
if(!this->connect()) this->openSoftAP();
return true;
}
void Network::loop() {
if(millis() - this->lastEmit > 1500) {
if(this->connect()) {}
this->lastEmit = millis();
this->emitSockets();
}
if(settings.WIFI.ssdpBroadcast) {
if(!SSDP.isStarted) SSDP.begin();
SSDP.loop();
}
else if(!settings.WIFI.ssdpBroadcast && SSDP.isStarted) SSDP.end();
mqtt.loop();
}
void Network::emitSockets() {
if(WiFi.status() == WL_CONNECTED) {
char buf[50];
sprintf(buf, "{\"ssid\":\"%s\", \"strength\":%d, \"channel\":%d}", WiFi.SSID(), WiFi.RSSI(), WiFi.channel());
sockEmit.sendToClients("wifiStrength", buf);
}
else
sockEmit.sendToClients("wifiStrength", "{\"ssid\":\"\", \"strength\":-100,\"channel\":-1}");
}
void Network::setConnected() {
WiFi.hostname(settings.WIFI.hostname);
this->ssid = WiFi.SSID();
this->mac = WiFi.BSSIDstr();
this->strength = WiFi.RSSI();
this->channel = WiFi.channel();
this->connectTime = millis();
if(this->connectAttempts == 1) {
Serial.println();
Serial.print("Successfully Connected to WiFi!!!!");
Serial.print(WiFi.localIP());
Serial.print(" (");
Serial.print(this->strength);
Serial.println("dbm)");
}
else {
Serial.println();
Serial.print("Reconnected after ");
Serial.print(1.0 * (millis() - this->connectStart)/1000);
Serial.print("sec IP: ");
Serial.print(WiFi.localIP());
Serial.print(" ");
Serial.print(this->mac);
Serial.print(" CH:");
Serial.print(this->channel);
Serial.print(" (");
Serial.print(this->strength);
Serial.print(" dBm)");
Serial.print(" Disconnected ");
Serial.print(this->connectAttempts - 1);
Serial.println(" times");
}
SSDP.setHTTPPort(80);
SSDP.setSchemaURL(0, "upnp.xml");
SSDP.setChipId(0, this->getChipId());
SSDP.setDeviceType(0, "urn:schemas-rstrouse-org:device:SomfyServer:1");
SSDP.setName(0, settings.WIFI.hostname);
//SSDP.setSerialNumber(0, "C2496952-5610-47E6-A968-2FC19737A0DB");
//SSDP.setUUID(0, settings.uuid);
SSDP.setModelName(0, "Somfy Server");
SSDP.setModelNumber(0, "SS v1");
SSDP.setModelURL(0, "https://github.com/rstrouse/ESP32-somfyServer");
SSDP.setManufacturer(0, "rstrouse");
SSDP.setManufacturerURL(0, "https://github.com/rstrouse");
SSDP.setURL(0, "/");
if(MDNS.begin(settings.WIFI.hostname)) {
Serial.println(F("MDNS Responder Started"));
MDNS.addService("_http", "_tcp", 80);
MDNS.addServiceTxt("_http", "_tcp", "board", "ESP32");
//MDNS.addServiceTxt("_osc", "_udp", "board", settings.WIFI.hostname);
}
if(settings.WIFI.ssdpBroadcast) {
if( SSDP.begin()) Serial.println("SSDP Client Started...");
}
else if(SSDP.isStarted) SSDP.end();
//digitalWrite(LED_BUILTIN, HIGH);
this->emitSockets();
}
bool Network::connect() {
if(settings.WIFI.hostname[0] != '\0') WiFi.hostname(settings.WIFI.hostname);
if(settings.WIFI.ssid[0] != '\0') {
if(WiFi.status() == WL_CONNECTED && WiFi.SSID().compareTo(settings.WIFI.ssid) == 0) {
this->disconnected = 0;
return true;
}
if(this->connectAttempts > 0) {
Serial.print("Connection Lost...");
Serial.print(this->mac);
Serial.print(" CH:");
Serial.print(this->channel);
Serial.print(" (");
Serial.print(this->strength);
Serial.print("dbm) ");
}
else Serial.println("Connecting to AP");
this->connectAttempts++;
this->connectStart = millis();
Serial.print("Set hostname to:");
Serial.println(WiFi.getHostname());
WiFi.mode(WIFI_STA);
delay(100);
WiFi.begin(settings.WIFI.ssid, settings.WIFI.passphrase);
delay(100);
int retries = 0;
while(retries < 100) {
//digitalWrite(LED_BUILTIN, retries % 2 ? HIGH : LOW); // Flash the LED while connecting
switch(WiFi.status()) {
case WL_SCAN_COMPLETED:
Serial.println("Status: Scan Completed");
break;
case WL_CONNECT_FAILED:
if(this->connectAttempts == 1) Serial.println();
Serial.println("WiFi Module connection failed");
return false;
case WL_DISCONNECTED:
break;
case WL_IDLE_STATUS:
Serial.print("*");
break;
case WL_CONNECTED:
this->setConnected();
delay(100);
return true;
case WL_NO_SHIELD:
Serial.println("Connection failed - WiFi module not found");
return false;
case WL_NO_SSID_AVAIL:
Serial.print(" Connection failed the SSID ");
Serial.print(settings.WIFI.ssid);
Serial.print(" could not be found");
return false;
}
delay(500);
if(connectAttempts == 1) Serial.print("*");
retries++;
}
if(this->connectAttempts != 1) {
int st = this->getStrengthBySSID(settings.WIFI.ssid);
Serial.print("(");
Serial.print(st);
Serial.print("dBm) ");
Serial.println("Failed");
//if(disconnected > 0 && st == -100) settings.WIFI.PrintNetworks();
disconnected++;
}
}
//digitalWrite(LED_BUILTIN, HIGH); // Turn off the LED.
return false;
}
int Network::getStrengthByMac(const char *macAddr) {
int strength = -100;
int n = WiFi.scanNetworks(true);
for(int i = 0; i < n; i++) {
if(WiFi.BSSIDstr(i).compareTo(macAddr) == 0) return WiFi.RSSI(i);
}
}
uint32_t Network::getChipId() {
uint32_t chipId = 0;
uint64_t mac = ESP.getEfuseMac();
for(int i=0; i<17; i=i+8) {
chipId |= ((mac >> (40 - i)) & 0xff) << i;
}
return chipId;
}
int Network::getStrengthBySSID(const char *ssid) {
int strength = -100;
int n = WiFi.scanNetworks(false, true);
for(int i = 0; i < n; i++) {
if(WiFi.SSID(i).compareTo(ssid) == 0) strength = max(WiFi.RSSI(i), strength);
}
if(strength == -100) {
Serial.print("Could not find network [");
Serial.print(ssid);
Serial.print("] Scanned ");
Serial.print(n);
Serial.println(" Networks...");
String network;
uint8_t encType;
int32_t RSSI;
uint8_t* BSSID;
int32_t channel;
bool isHidden;
for(int i = 0; i < n; i++) {
//WiFi.getNetworkInfo(i, network, encType, RSSI, BSSID, channel, isHidden);
if(network.compareTo(this->ssid) == 0) Serial.print("*");
else Serial.print(" ");
Serial.print(i);
Serial.print(": ");
Serial.print(WiFi.SSID(i).c_str());
Serial.print(" (");
Serial.print(WiFi.RSSI(i));
Serial.print("dBm) CH:");
Serial.print(WiFi.channel(i));
Serial.print(" MAC:");
Serial.print(WiFi.BSSIDstr(i).c_str());
if(isHidden) Serial.print(" [hidden]");
Serial.println();
}
}
return strength;
}
bool Network::openSoftAP() {
Serial.println();
Serial.println("Turning the HotSpot On");
WiFi.disconnect(true);
WiFi.mode(WIFI_AP_STA);
delay(100);
WiFi.softAP("Somfy Controller", "");
Serial.println("Initializing AP for credentials modification");
Serial.println();
Serial.print("SoftAP IP: ");
Serial.println(WiFi.softAPIP());
pinMode(D0, INPUT_PULLUP);
long startTime = millis();
int c = 0;
while ((WiFi.status() != WL_CONNECTED))
{
for(int i = 0; i < 3; i++) {
delay(100);
//digitalWrite(LED_BUILTIN, HIGH);
delay(100);
//digitalWrite(LED_BUILTIN, LOW);
}
int clients = WiFi.softAPgetStationNum();
if(clients > 0)
Serial.print(clients);
else
Serial.print(".");
delay(100);
webServer.loop();
// If no clients have connected in 3 minutes from starting this server reboot this pig. This will
// force a reboot cycle until we have some response. That is unless the SSID has been cleared.
if(clients == 0 && strlen(settings.WIFI.ssid) > 0 && millis() - startTime > 3 * 60000) {
Serial.println();
Serial.println("Stopping AP Mode");
WiFi.softAPdisconnect(true);
return false;
}
if(digitalRead(D0) == LOW) {
Serial.println();
Serial.println("Button Pressed...Stopping AP Mode");
WiFi.softAPdisconnect(true);
return false;
}
if(++c % 100 == 0) {
Serial.println();
}
}
}

28
Network.h Normal file
View file

@ -0,0 +1,28 @@
#include <Arduino.h>
#ifndef Network_h
#define Network_h
class Network {
protected:
unsigned long lastEmit = 0;
public:
String ssid;
String mac;
int channel;
int strength;
int disconnected = 0;
int connectAttempts = 0;
long connectStart = 0;
long connectTime = 0;
bool openSoftAP();
bool connect();
void setConnected();
int getStrengthByMac(const char *mac);
int getStrengthBySSID(const char *ssid);
bool setup();
void loop();
void end();
void emitSockets();
uint32_t getChipId();
};
#endif

856
SSDP.cpp Normal file
View file

@ -0,0 +1,856 @@
#include <functional>
#include <AsyncUDP.h>
#include "Utils.h"
#include "ConfigSettings.h"
#include "SSDP.h"
#define SSDP_PORT 1900
#define SSDP_METHOD_SIZE 10
#define SSDP_URI_SIZE 2
#define SSDP_BUFFER_SIZE 64
#define SSDP_MULTICAST_ADDR 239, 255, 255, 250
extern ConfigSettings settings;
static const char _ssdp_uuid_template[] PROGMEM = "C2496952-5610-47E6-A968-2FC1%02x%02x%02x%02x";
static const char _ssdp_serial_number_template[] PROGMEM = "ESP32-%02x%02x%02x";
static const char _ssdp_usn_root_template[] PROGMEM = "%s::upnp::rootdevice";
static const char _ssdp_usn_uuid_template[] PROGMEM = "%s::%s";
static const char _ssdp_response_template[] PROGMEM =
"HTTP/1.1 200 OK\r\n"
"EXT:\r\n";
static const char _ssdp_notify_template[] PROGMEM =
"NOTIFY * HTTP/1.1\r\n"
"HOST: 239.255.255.250:1900\r\n"
"NTS: ssdp:alive\r\n";
static const char _ssdp_bye_template[] PROGMEM =
"NOTIFY * HTTP/1.1\r\n"
"HOST: 239.255.255.250:1900\r\n"
"NTS: ssdp:byebye\r\n";
static const char _ssdp_packet_template[] PROGMEM =
"%s" // _ssdp_response_template / _ssdp_notify_template
"CACHE-CONTROL: max-age=%u\r\n" // _interval
"SERVER: Arduino/1.0 UPNP/1.1 %s/%s\r\n" // _modelName, _modelNumber
"USN: %s\r\n" // _uuid
"%s: %s\r\n" // "NT" or "ST", _deviceType
"LOCATION: http://%u.%u.%u.%u:%u/%s\r\n" // WiFi.localIP(), _port, _schemaURL
"\r\n";
static const char _ssdp_device_schema_template[] PROGMEM =
"<device>"
"<deviceType>%s</deviceType>"
"<friendlyName>%s</friendlyName>"
"<presentationURL>%s</presentationURL>"
"<serialNumber>%s</serialNumber>"
"<modelName>%s</modelName>"
"<modelNumber>%s</modelNumber>"
"<modelURL>%s</modelURL>"
"<manufacturer>%s</manufacturer>"
"<manufacturerURL>%s</manufacturerURL>"
"<modelDescription>Somfy RTS Controller</modelDescription>"
"<firmwareVersion>%s</firmwareVersion>"
"<UDN>%s</UDN>"
"<serviceList></serviceList>"
"<deviceList></deviceList>"
"</device>";
static const char _ssdp_schema_template[] PROGMEM =
"HTTP/1.1 200 OK\r\n"
"Content-Type: text/xml\r\n"
"Connection: close\r\n"
"Access-Control-Allow-Origin: *\r\n"
"\r\n"
"<?xml version=\"1.0\"?>"
"<root xmlns=\"urn:schemas-upnp-org:device-1-0\">"
"<specVersion>"
"<major>1</major>"
"<minor>0</minor>"
"</specVersion>"
"<URLBase>http://%s:%u/</URLBase>"; // WiFi.localIP(), _port
UPNPDeviceType::UPNPDeviceType() {
lastNotified = 0;
schemaURL[0] = '\0';
uuid[0] = '\0';
deviceType[0] = '\0';
friendlyName[0] = '\0';
serialNumber[0] = '\0';
presentationURL[0] = '\0';
manufacturer[0] = '\0';
manufacturerURL[0] = '\0';
modelName[0] = '\0';
modelURL[0] = '\0';
modelNumber[0] = '\0';
m_usn[0] = '\0';
isActive = true;
}
UPNPDeviceType::UPNPDeviceType(const char *deviceType) { this->setDeviceType(deviceType); }
UPNPDeviceType::UPNPDeviceType(const char *deviceType, const char *uuid){ this->setDeviceType(deviceType); this->setUUID(uuid); }
UPNPDeviceType::UPNPDeviceType(const char *deviceType, const char *uuid, const char*friendlyName) { this->setDeviceType(deviceType); this->setUUID(uuid); this->setName(friendlyName);}
void UPNPDeviceType::setSchemaURL(const char *url) { strlcpy(schemaURL, url, sizeof(schemaURL)); }
void UPNPDeviceType::setDeviceType(const char *dtype) { strlcpy(deviceType, dtype, sizeof(deviceType)); }
void UPNPDeviceType::setUUID(const char *id) { snprintf_P(uuid, sizeof(uuid), PSTR("uuid:%s"), id); }
void UPNPDeviceType::setName(const char *name) { strlcpy(friendlyName, name, sizeof(friendlyName)); }
void UPNPDeviceType::setURL(const char *url) { strlcpy(presentationURL, url, sizeof(presentationURL)); }
void UPNPDeviceType::setSerialNumber(const char *sn) { strlcpy(serialNumber, sn, sizeof(serialNumber)); }
void UPNPDeviceType::setSerialNumber(const uint32_t sn) { snprintf(serialNumber, sizeof(uint32_t) * 2 + 1, "%08X", sn); }
void UPNPDeviceType::setModelName(const char *name) { strlcpy(modelName, name, sizeof(modelName)); }
void UPNPDeviceType::setModelNumber(const char *num) { strlcpy(modelNumber, num, sizeof(modelNumber));}
void UPNPDeviceType::setModelURL(const char *url) { strlcpy(modelURL, url, sizeof(modelURL)); }
void UPNPDeviceType::setManufacturer(const char *name) { strlcpy(manufacturer, name, sizeof(manufacturer)); }
void UPNPDeviceType::setManufacturerURL(const char *url) { strlcpy(manufacturerURL, url, sizeof(manufacturerURL)); }
//char * UPNPDeviceType::getUSN() { return this->getUSN(this->deviceType); }
char * UPNPDeviceType::getUSN(const char *st) {
#ifdef DEBUG_SSDP
DEBUG_SSDP.print("GETUSN ST: ");
DEBUG_SSDP.println(st);
DEBUG_SSDP.print("GETUSN UUID: ");
DEBUG_SSDP.println(this->uuid);
DEBUG_SSDP.print("sizeof(this->m_usn)");
DEBUG_SSDP.println(sizeof(this->m_usn));
memset(this->m_usn, 0x00, sizeof(this->m_usn));
#endif
if(strncmp("upnp:root", st, strlen(st)) == 0) {
snprintf_P(this->m_usn, sizeof(this->m_usn) - 1, _ssdp_usn_root_template, this->uuid);
}
else {
snprintf_P(this->m_usn, sizeof(this->m_usn) - 1, _ssdp_usn_uuid_template, this->uuid, st);
}
#ifdef DEBUG_SSDP
DEBUG_SSDP.print("RESUSN UUID: ");
DEBUG_SSDP.println(this->m_usn);
#endif
return this->m_usn;
}
void UPNPDeviceType::setChipId(uint32_t chipId) {
snprintf_P(this->uuid, sizeof(this->uuid), _ssdp_uuid_template,
0x40,
(uint16_t)((chipId >> 16) & 0xff),
(uint16_t)((chipId >> 8) & 0xff),
(uint16_t)chipId & 0xff);
snprintf_P(this->serialNumber, sizeof(this->serialNumber),
_ssdp_serial_number_template,
(uint16_t)((chipId >> 16) & 0xff),
(uint16_t)((chipId >> 8) & 0xff),
(uint16_t)chipId & 0xff);
}
SSDPClass::SSDPClass():sendQueue{NULL} {}
SSDPClass::~SSDPClass() { end(); }
bool SSDPClass::begin() {
for(int i = 0; i < SSDP_QUEUE_SIZE; i++) {
this->sendQueue[i].waiting = false;
}
this->end();
//assert(NULL == _server);
if(_server.connected()) {
#ifdef DEBUG_SSDP
DEBUG_SSDP.println(PSTR("Already connected to SSDP."));
this->isStarted = true;
#endif
return false;
}
_server.onPacket([](void * arg, AsyncUDPPacket& packet) { ((SSDPClass*)(arg))->_processRequest(packet); }, this);
if(!_server.listenMulticast(IPAddress(SSDP_MULTICAST_ADDR), SSDP_PORT)) {
#ifdef DEBUG_SSDP
IPAddress mcast(SSDP_MULTICAST_ADDR);
DEBUG_SSDP.println(PSTR("Error starting SSDP listener on:"));
DEBUG_SSDP.print(mcast);
DEBUG_SSDP.print(":");
DEBUG_SSDP.println(SSDP_PORT);
#endif
return false;
}
this->isStarted = true;
this->_sendByeBye();
this->_sendNotify();
Serial.println("Connected to SSDP");
return true;
}
void SSDPClass::end() {
if(!this->_server || !this->_server.connected()) return; // server isn't connected nothing to do
#ifdef DEBUG_SSDP
DEBUG_SSDP.printf(PSTR("SSDP end ... "));
#endif
this->_sendByeBye();
//this->_stopTimer();
this->_server.close();
this->isStarted = false;
Serial.println("Disconnected from SSDP");
}
UPNPDeviceType* SSDPClass::getDeviceType(uint8_t ndx) { if(ndx < this->m_cdeviceTypes) return &this->deviceTypes[ndx]; return nullptr; }
UPNPDeviceType* SSDPClass::findDeviceByType(char *devType) {
for(uint8_t i = 0; i < this->m_cdeviceTypes; i++) {
if (strcasecmp(devType, this->deviceTypes[i].deviceType) == 0) return &this->deviceTypes[i];
}
return nullptr;
}
UPNPDeviceType* SSDPClass::findDeviceByUUID(char *uuid) {
for(uint8_t i = 0; i < this->m_cdeviceTypes; i++) {
if (strcasecmp(uuid, this->deviceTypes[i].uuid) == 0) return &this->deviceTypes[i];
}
return nullptr;
}
bool SSDPClass::_startsWith(const char *sw, const char *str) { return strncmp(sw, str, strlen(sw)) == 0; }
void SSDPClass::_parsePacket(ssdp_packet_t *pkt, AsyncUDPPacket &p) {
//MSEARCH = "M-SEARCH * HTTP/1.1\nHost: 239.255.255.250:1900\nMan: \"ssdp:discover\"\nST: roku:ecp\n";
memset(pkt, 0x00, sizeof(ssdp_packet_t));
pkt->method = NONE;
pkt->type = UNKNOWN;
pkt->recvd = millis();
pkt->valid = true;
char buffer[SSDP_BUFFER_SIZE] = {0};
uint8_t pos = 0;
while(p.available() > 0) {
char c = p.read();
if(pkt->method == NONE) {
if(c == ' ') {
_trim(buffer);
pos = 0;
if(strcmp(buffer, "M-SEARCH") == 0) pkt->method = SEARCH;
else if(strcmp(buffer, "NOTIFY") == 0) pkt->method = NOTIFY;
}
else {
if(pos < SSDP_BUFFER_SIZE - 1) {
buffer[pos++] = c;
buffer[pos] = '\0';
}
}
}
else {
if(c == '\r' || c == '\n') {
_trim(buffer);
if(strcasecmp(buffer, "* HTTP/1.1") != 0) pkt->valid = false;
break;
}
else {
if(pos < SSDP_BUFFER_SIZE) {
buffer[pos++] = c;
buffer[pos] = '\0';
}
}
}
if(c == ' ' && pkt->method == NONE) {
pkt->valid = false;
break; // We didn't get a method we want.
}
}
enum {KEY, HOST, MAN, ST, MX, AGENT, HEAD, SERVER, NTS, LOCATION, USN, NT} keys;
keys = KEY;
if(pkt->method == SEARCH) {
// Get all the key:value pairs
pos = 0;
buffer[0] = '\0';
while(p.available() > 0) {
char c = p.read();
//#ifdef DEBUG_SSDP_PACKET
//DEBUG_SSDP.print(c);
//#endif
if(keys == KEY) {
if(c == ':') {
_trim(buffer);
if(strcasecmp(buffer, "MAN") == 0) keys = MAN;
else if(strcasecmp(buffer, "ST") == 0) keys = ST;
else if(strcasecmp(buffer, "MX") == 0) keys = MX;
else if(strcasecmp(buffer, "HOST") == 0) keys = HOST;
else if(strcasecmp(buffer, "USER-AGENT") == 0) keys = AGENT;
else if(strcasecmp(buffer, "SERVER") == 0) keys = SERVER;
else if(strcasecmp(buffer, "NTS") == 0) keys = NTS;
else if(strcasecmp(buffer, "NT") == 0) keys = NT;
else if(strcasecmp(buffer, "LOCATION") == 0) keys = LOCATION;
else if(strcasecmp(buffer, "USN") == 0) keys = USN;
else keys = HEAD;
//#ifdef DEBUG_SSDP_PACKET
//DEBUG_SSDP.printf("Found a key: %s ", buffer);
//#endif
pos = 0;
buffer[0] = '\0';
}
else if(c == '\r' || c == '\n') {
// If we find a key that ends before a : then we need to bugger out.
keys = KEY;
pos = 0;
buffer[0] = '\0';
//break;
}
else {
if(pos < SSDP_BUFFER_SIZE - 1) {
buffer[pos++] = c;
buffer[pos] = '\0';
}
}
}
else {
// We are reading a value
if(c == '\r' || c == '\n') {
_trim(buffer);
#ifdef DEBUG_SSDP_PACKET
DEBUG_SSDP.println(buffer);
#endif
switch(keys) {
case HOST:
if(strcasecmp(buffer, "239.255.255.250:1900") == 0) pkt->type = MULTICAST;
else pkt->type = UNICAST;
strcpy(pkt->host, buffer);
break;
case MAN:
strcpy(pkt->man, buffer);
break;
case ST:
strcpy(pkt->st, buffer);
break;
case MX:
pkt->mx = atoi(buffer);
break;
case AGENT:
strcpy(pkt->agent, buffer);
break;
}
keys = KEY;
pos = 0;
buffer[0] = '\0';
}
else {
if(pos < SSDP_BUFFER_SIZE - 1) {
buffer[pos++] = c;
buffer[pos] = '\0';
}
}
}
}
}
if(pkt->valid) {
if(pkt->method == NONE) pkt->valid = false;
if(pkt->method == SEARCH) {
#ifdef DEBUG_SSDP_PACKET
//this->_printPacket(pkt);
#endif
if(strcmp(pkt->man, "ssdp:discover") != 0) pkt->valid = false;
if(strlen(pkt->st) == 0) pkt->valid = false;
else if(strcmp(pkt->st, "ssdp:all") != 0 &&
strcmp(pkt->st, "upnp:rootdevice") != 0 &&
!this->_startsWith("uuid:", pkt->st) &&
!this->_startsWith("urn:", pkt->st))
pkt->valid = false;
if(pkt->type == UNICAST) {
if(strlen(pkt->host) == 0) pkt->valid = false;
}
else if(pkt->type == MULTICAST) {
if(pkt->mx == 0 || isnan(pkt->mx)) pkt->valid = false;
}
}
else if(pkt->method == NOTIFY) {
// This is somebody else's notify so we should blow it off.
}
else {
pkt->valid = false;
}
}
}
IPAddress SSDPClass::localIP()
{
// Make sure we don't get a null IPAddress.
tcpip_adapter_ip_info_t ip;
if (WiFi.getMode() == WIFI_STA) {
if (tcpip_adapter_get_ip_info(TCPIP_ADAPTER_IF_STA, &ip)) {
return IPAddress();
}
} else if (WiFi.getMode() == WIFI_OFF) {
if (tcpip_adapter_get_ip_info(TCPIP_ADAPTER_IF_ETH, &ip)) {
return IPAddress();
}
}
return IPAddress(ip.ip.addr);
}
void SSDPClass::_sendResponse(IPAddress addr, uint16_t port, UPNPDeviceType *d, char *st, bool sendUUID) {
char buffer[1460];
IPAddress ip = this->localIP();
//IPAddress ip = WiFi.localIP();
char *pbuff = (char *)malloc(strlen_P(_ssdp_response_template)+1);
if(!pbuff) {
#ifdef DEBUG_SSDP
DEBUG_SSDP.println("Out of memory for SSDP response");
#endif
return;
}
strcpy_P(pbuff, _ssdp_response_template);
#ifdef DEBUG_SSDP
//3FFC40B8
DEBUG_SSDP.println("Before sprintf ");
DEBUG_SSDP.print("CACHE-CONTROL: max-age=");
DEBUG_SSDP.println(this->_interval);
DEBUG_SSDP.print("SERVER: Arduino/1.0 UPNP/1.1 ");
DEBUG_SSDP.print(d->modelName);
DEBUG_SSDP.print("/");
DEBUG_SSDP.println(d->modelNumber);
DEBUG_SSDP.print("USN: ");
DEBUG_SSDP.println(d->getUSN(st));
DEBUG_SSDP.print("ST: ");
DEBUG_SSDP.println((sendUUID) ? d->uuid : st);
DEBUG_SSDP.print("LOCATION: http://");
DEBUG_SSDP.print(ip[0]);
DEBUG_SSDP.print(ip[1]);
DEBUG_SSDP.print(ip[2]);
DEBUG_SSDP.print(ip[3]);
DEBUG_SSDP.print(":");
DEBUG_SSDP.print(this->_port);
DEBUG_SSDP.println(d->schemaURL);
#endif
// Don't use ip.toString as this fragments the heap like no tomorrow.
int len = snprintf_P(buffer, sizeof(buffer)-1,
_ssdp_packet_template,
pbuff,
this->_interval,
d->modelName, d->modelNumber,
d->getUSN(st),
"ST", (sendUUID) ? d->uuid : st,
ip[0], ip[1], ip[2], ip[3], this->_port, d->schemaURL);
#ifdef DEBUG_SSDP
DEBUG_SSDP.println(buffer);
#endif
free(pbuff);
/*
static const char _ssdp_packet_template[] PROGMEM =
"%s" // _ssdp_response_template / _ssdp_notify_template
"CACHE-CONTROL: max-age=%u\r\n" // _interval
"SERVER: Arduino/1.0 UPNP/1.1 %s/%s\r\n" // _modelName, _modelNumber
"USN: %s\r\n" // _uuid
"%s: %s\r\n" // "NT" or "ST", _deviceType
"LOCATION: http://%u.%u.%u.%u:%u/%s\r\n" // WiFi.localIP(), _port, _schemaURL
"\r\n";
*/
buffer[sizeof(buffer) - 1] = '\0';
#ifdef DEBUG_SSDP
DEBUG_SSDP.print("Sending Response to ");
DEBUG_SSDP.print(IPAddress(addr));
DEBUG_SSDP.print(":");
DEBUG_SSDP.println(port);
DEBUG_SSDP.println(buffer);
#endif
_server.writeTo((const uint8_t *)buffer, len, addr, port);
}
void SSDPClass::_sendNotify() {
for(uint8_t i = 0; i < this->m_cdeviceTypes; i++) {
UPNPDeviceType *dev = &this->deviceTypes[i];
if(strlen(dev->deviceType) > 0 && dev->isActive) {
uint16_t elapsed = (millis() - dev->lastNotified);
if(!dev->lastNotified || (elapsed * 4) > (this->_interval * 1000)) {
#ifdef DEBUG_SSDP
DEBUG_SSDP.print(dev->deviceType);
DEBUG_SSDP.print(" Time since last notified: ");
DEBUG_SSDP.print(elapsed);
DEBUG_SSDP.print("msec ");
DEBUG_SSDP.print(this->_interval);
DEBUG_SSDP.println("msec");
#endif
this->_sendNotify(dev, i == 0);
}
else {
#ifdef DEBUG_SSDP
DEBUG_SSDP.print(dev->deviceType);
DEBUG_SSDP.print(" Time since last notified: ");
DEBUG_SSDP.print(elapsed/1000);
DEBUG_SSDP.print("msec ");
DEBUG_SSDP.print(this->_interval);
DEBUG_SSDP.println("msec -- SKIPPING");
#endif
}
}
}
}
void SSDPClass::_sendNotify(const char *msg) {
//_server->append(msg, strlen(msg));
//_server->send(IPAddress(SSDP_MULTICAST_ADDR), SSDP_PORT);
_server.writeTo((uint8_t *)msg, strlen(msg), IPAddress(SSDP_MULTICAST_ADDR), SSDP_PORT);
}
void SSDPClass::_sendNotify(UPNPDeviceType *d) { this->_sendByeBye(d, strcmp(d->deviceType, this->deviceTypes[0].deviceType) == 0); }
void SSDPClass::_sendNotify(UPNPDeviceType *d, bool root) {
char buffer[1460];
IPAddress ip = this->localIP();
/*
"NOTIFY * HTTP/1.1\r\n"
"HOST: 239.255.255.250:1900\r\n"
"NTS: ssdp:alive\r\n";
"CACHE-CONTROL: max-age=%u\r\n" // _interval
"SERVER: Arduino/1.0 UPNP/1.1 %s/%s\r\n" // _modelName, _modelNumber
"USN: %s\r\n" // _uuid
"%s: %s\r\n" // "NT" or "ST", _deviceType
"LOCATION: http://%s:%u/%s\r\n" // WiFi.localIP(), _port, _schemaURL
*/
char *pbuff = (char *)malloc(strlen_P(_ssdp_notify_template)+1);
if(!pbuff) {
#ifdef DEBUG_SSDP
DEBUG_SSDP.println(PSTR("Out of memory for SSDP response"));
#endif
return;
}
strcpy_P(pbuff, _ssdp_response_template);
#ifdef DEBUG_SSDP
//3FFC40B8
DEBUG_SSDP.print("Before Notify sprintf ");
DEBUG_SSDP.print((uintptr_t)d, HEX);
DEBUG_SSDP.println(" ");
#endif
if(root) {
// Send 1 for root
snprintf_P(buffer, sizeof(buffer),
_ssdp_packet_template,
pbuff,
this->_interval,
d->modelName, d->modelNumber,
d->getUSN("upnp:rootdevice"), // USN
"NT", "upnp:rootdevice",
ip[0], ip[1], ip[2], ip[3], this->_port, d->schemaURL);
this->_sendNotify(buffer);
}
else {
// Send 1 for uuid
snprintf_P(buffer, sizeof(buffer),
_ssdp_packet_template,
pbuff,
this->_interval,
d->modelName,
d->modelNumber,
d->uuid,
"NT", d->uuid,
ip[0], ip[1], ip[2], ip[3], _port, d->schemaURL);
this->_sendNotify(buffer);
// Send 1 for deviceType
snprintf_P(buffer, sizeof(buffer),
_ssdp_packet_template,
pbuff,
this->_interval,
d->modelName,
d->modelNumber,
d->getUSN(d->deviceType),
"NT", d->deviceType,
ip[0], ip[1], ip[2], ip[3], _port, d->schemaURL);
this->_sendNotify(buffer);
}
d->lastNotified = millis();
}
void SSDPClass::setActive(uint8_t ndx, bool isActive) {
UPNPDeviceType *d = &this->deviceTypes[ndx];
if(!isActive) this->_sendByeBye(d, ndx == 0);
else {
d->isActive = true;
d->lastNotified = 0;
this->_sendNotify(d, ndx == 0);
}
}
void SSDPClass::_sendByeBye() {
for(uint8_t i = 0; i < this->m_cdeviceTypes; i++) {
UPNPDeviceType *dev = &this->deviceTypes[i];
if(strlen(dev->deviceType) > 0) {
#ifdef DEBUG_SSDP
DEBUG_SSDP.print(dev->deviceType);
//DEBUG_SSDP.print(" Time since last notified: ");
//DEBUG_SSDP.print(elapsed);
//DEBUG_SSDP.print("msec ");
DEBUG_SSDP.print(this->_interval);
DEBUG_SSDP.println("msec");
#endif
this->_sendByeBye(dev, i == 0);
}
}
}
void SSDPClass::_sendByeBye(const char *msg) {
//_server->append(msg, strlen(msg));
//_server->send(IPAddress(SSDP_MULTICAST_ADDR), SSDP_PORT);
_server.writeTo((uint8_t *)msg, strlen(msg), IPAddress(SSDP_MULTICAST_ADDR), SSDP_PORT);
}
void SSDPClass::_sendByeBye(UPNPDeviceType *d) { this->_sendByeBye(d, strcmp(d->deviceType, this->deviceTypes[0].deviceType) == 0); }
void SSDPClass::_sendByeBye(UPNPDeviceType *d, bool root) {
char buffer[1460];
IPAddress ip = this->localIP();
/*
"NOTIFY * HTTP/1.1\r\n"
"HOST: 239.255.255.250:1900\r\n"
"NTS: ssdp:byebye\r\n";
"CACHE-CONTROL: max-age=%u\r\n" // _interval
"SERVER: Arduino/1.0 UPNP/1.1 %s/%s\r\n" // _modelName, _modelNumber
"USN: %s\r\n" // _uuid
"%s: %s\r\n" // "NT" or "ST", _deviceType
"LOCATION: http://%s:%u/%s\r\n" // WiFi.localIP(), _port, _schemaURL
*/
if(root) {
// Send 1 for root
snprintf_P(buffer, sizeof(buffer)-1,
_ssdp_packet_template,
_ssdp_notify_template,
this->_interval,
d->modelName, d->modelNumber,
d->getUSN("upnp:rootdevice"), // USN
"NT", "upnp:rootdevice",
ip[0], ip[1], ip[2], ip[3], this->_port, d->schemaURL);
this->_sendNotify(buffer);
}
else {
// Send 1 for uuid
snprintf_P(buffer, sizeof(buffer)-1,
_ssdp_packet_template,
_ssdp_notify_template,
this->_interval,
d->modelName,
d->modelNumber,
d->uuid,
"NT", d->uuid,
ip[0], ip[1], ip[2], ip[3], this->_port, d->schemaURL);
this->_sendNotify(buffer);
// Send 1 for deviceType
snprintf_P(buffer, sizeof(buffer)-1,
_ssdp_packet_template,
_ssdp_notify_template,
this->_interval,
d->modelName,
d->modelNumber,
d->getUSN(d->deviceType),
"NT", d->deviceType,
ip[0], ip[1], ip[2], ip[3], this->_port, d->schemaURL);
this->_sendNotify(buffer);
}
d->isActive = false;
}
void SSDPClass::_addToSendQueue(IPAddress addr, uint16_t port, UPNPDeviceType *d, char *st, uint8_t sec, bool sendUUID) {
/*
typedef struct ssdp_response_t {
IPAddress address;
uint16_t port;
UPNPDeviceType *dev;
bool sendUUID;
unsigned long sendTime;
char st[SSDP_DEVICE_TYPE_SIZE];
};
*/
for(uint8_t i = 0; i < SSDP_QUEUE_SIZE; i++) {
if(this->sendQueue[i].waiting) {
// Check to see if this is a reply to the same place.
ssdp_response_t *q = &this->sendQueue[i];
if(q->address == addr && q->port == port && q->sendUUID == sendUUID) {
#ifdef DEBUG_SSDP
DEBUG_SSDP.printf("There is already a response to this query in slot #u\n", i);
#endif
return;
}
}
}
// Find an empty queue slot and fill it.
for(uint8_t i = 0; i < SSDP_QUEUE_SIZE; i++) {
if(!this->sendQueue[i].waiting) {
#ifdef DEBUG_SSDP
DEBUG_SSDP.printf("Queueing SSDP response in slot %u\n", i);
DEBUG_SSDP.println("*********************************");
#endif
ssdp_response_t *q = &this->sendQueue[i];
q->dev = d;
q->sendTime = millis() + (random(0, sec - 1) * 1000L);
q->address = addr;
q->port = _port;
q->sendUUID = sendUUID;
strlcpy(q->st, st, sizeof(ssdp_response_t::st)-1);
q->waiting = true;
return;
}
}
// If we made it here then there were was not space available on the queue.
#ifdef DEBUG_SSDP
DEBUG_SSDP.println("The SSDP response queue was full. Dropping request");
#endif
}
void SSDPClass::_sendQueuedResponses() {
for(uint8_t i = 0; i < SSDP_QUEUE_SIZE; i++) {
if(this->sendQueue[i].waiting) {
ssdp_response_t *q = &this->sendQueue[i];
if(q->sendTime < millis()) {
// Send the response and delete the pointer.
#ifdef DEBUG_SSDP
DEBUG_SSDP.print("Sending SSDP queued response ");
DEBUG_SSDP.println(i);
#endif
this->_sendResponse(q->address, q->port, q->dev, q->st, q->sendUUID);
q->waiting = false;
return;
}
}
}
}
void SSDPClass::_printPacket(ssdp_packet_t *pkt) {
Serial.printf("Rec: %d\n", pkt->recvd);
switch(pkt->method) {
case NONE:
Serial.println("Method: NONE");
break;
case SEARCH:
Serial.println("Method: SEARCH");
break;
case NOTIFY:
Serial.println("Method: NOTIFY");
break;
default:
Serial.println("Method: UNKOWN");
break;
}
Serial.printf("ST: %s\n", pkt->st);
Serial.printf("MAN: %s\n", pkt->man);
Serial.printf("AGENT: %s\n", pkt->agent);
Serial.printf("HOST: %s\n", pkt->host);
Serial.printf("MX: %d\n", pkt->mx);
Serial.printf("type: %d\n", pkt->type);
Serial.printf("valid: %d\n", pkt->valid);
}
void SSDPClass::_processRequest(AsyncUDPPacket &p) {
// This pending BS should probably be for unicast request only but we will play along for now.
if(p.length() == 0) {
//this->_sendQueuedResponses();
return;
}
ssdp_packet_t pkt;
this->_parsePacket(&pkt, p);
if(pkt.valid && pkt.method == SEARCH) {
// Check to see if we have anything to respond to from this packet.
if(strcmp("ssdp:all", pkt.st) == 0) {
for(uint8_t i = 0; i < this->m_cdeviceTypes; i++) {
if(strlen(this->deviceTypes[i].deviceType) > 0)
this->_addToSendQueue(p.remoteIP(), p.remotePort(), &this->deviceTypes[i], this->deviceTypes[i].deviceType, pkt.mx, false);
}
}
else if(strcmp("upnp:rootdevice", pkt.st) == 0) {
UPNPDeviceType *dev = &this->deviceTypes[0];
#ifdef DEBUG_SSDP
this->_printPacket(&pkt);
DEBUG_SSDP.println("--------------- ROOT ---------------------");
#endif
if(pkt.method == MULTICAST)
this->_addToSendQueue(IPAddress(SSDP_MULTICAST_ADDR), SSDP_PORT, dev, pkt.st, pkt.mx, false);
else
this->_sendResponse(p.remoteIP(), p.remotePort(), dev, pkt.st, false);
}
else {
UPNPDeviceType *dev;
bool useUUID = false;
if(this->_startsWith("uuid:", pkt.st)) {
dev = this->findDeviceByUUID(pkt.st);
useUUID = true;
}
else if(this->_startsWith("urn:", pkt.st)) { dev = this->findDeviceByType(pkt.st); }
if(dev) {
#ifdef DEBUG_SSDP
this->_printPacket(&pkt);
DEBUG_SSDP.println("-------------- ACCEPT --------------------");
#endif
if(pkt.method == MULTICAST)
this->_addToSendQueue(IPAddress(SSDP_MULTICAST_ADDR), SSDP_PORT, dev, pkt.st, pkt.mx, useUUID);
else {
this->_sendResponse(p.remoteIP(), p.remotePort(), dev, pkt.st, useUUID);
}
}
}
}
else if(pkt.method == SEARCH) {
}
}
void SSDPClass::loop() {
this->_sendQueuedResponses();
}
void SSDPClass::schema(Print &client) {
IPAddress ip = WiFi.localIP();
uint8_t devCount = 0;
for(uint8_t i = 0; i < this->m_cdeviceTypes; i++) {
if(this->deviceTypes[i].deviceType && strlen(this->deviceTypes[i].deviceType) > 0) devCount++;
}
char schema_template[strlen_P(_ssdp_schema_template)+1];
char device_template[strlen_P(_ssdp_device_schema_template)+1];
strcpy_P(schema_template, _ssdp_schema_template);
strcpy_P(device_template, _ssdp_device_schema_template);
char buff[sizeof(device_template) + sizeof(UPNPDeviceType)];
buff[0] = '\0';
client.printf(schema_template,
ip.toString().c_str(), _port);
UPNPDeviceType *r = &this->deviceTypes[0];
sprintf(buff, device_template,
r->deviceType,
r->friendlyName,
r->presentationURL,
r->serialNumber,
r->modelName,
r->modelNumber,
r->modelURL,
r->manufacturer,
r->manufacturerURL,
settings.fwVersion,
r->uuid );
char *devList = strstr(buff, "</device>") - strlen("</deviceList>");
devList[0] = '\0';
client.print(buff);
for(uint8_t i = 1; i < this->m_cdeviceTypes; i++) {
UPNPDeviceType *dev = &this->deviceTypes[i];
if(strlen(dev->deviceType) > 0) {
//Serial.print(devList);
client.printf(device_template,
dev->deviceType,
dev->friendlyName,
dev->presentationURL,
dev->serialNumber,
dev->modelName,
dev->modelNumber,
dev->modelURL,
dev->manufacturer,
dev->manufacturerURL,
settings.fwVersion,
dev->uuid);
}
}
client.print(F("</deviceList></device></root>\r\n"));
#ifdef DEBUG_SSDP
DEBUG_SSDP.println("Sending Device.xml");
#endif
}
/*
void SSDPClass::setDeviceType(uint8_t ndx, UPNPDeviceType *dt) {
this->setDeviceType(ndx, dt->deviceType);
this->setName(ndx, dt->friendlyName);
this->setURL(ndx, dt->presentationURL);
this->setSerialNumber(ndx, dt->serialNumber);
this->setUUID(ndx, dt->uuid);
this->setModelName(ndx, dt->modelName);
this->setModelNumber(ndx, dt->modelNumber);
this->setManufacturer(ndx, dt->manufacturer);
this->setManufacturerURL(ndx, dt->manufacturerURL);
}
*/
void SSDPClass::setTTL(const uint8_t ttl) { _ttl = ttl; }
void SSDPClass::setHTTPPort(uint16_t port) { _port = port; }
void SSDPClass::setInterval(uint32_t interval) { _interval = interval; }
void SSDPClass::setDeviceType(uint8_t ndx, const char *type) { this->deviceTypes[ndx].setDeviceType(type); }
void SSDPClass::setSchemaURL(uint8_t ndx, const char *url) { this->deviceTypes[ndx].setSchemaURL(url); }
void SSDPClass::setUUID(uint8_t ndx, const char *uuid) { this->deviceTypes[ndx].setUUID(uuid); }
void SSDPClass::setUUID(uint8_t ndx, const char *prefix, uint32_t id) {
char svcuuid[50];
sprintf(svcuuid, "%s%02x%02x%02x",
prefix,
(uint16_t)((id >> 16) & 0xff),
(uint16_t)((id >> 8) & 0xff),
(uint16_t)id & 0xff);
this->setUUID(ndx, svcuuid);
}
void SSDPClass::setName(uint8_t ndx, const char *name) { this->deviceTypes[ndx].setName(name); }
void SSDPClass::setURL(uint8_t ndx, const char *url) { this->deviceTypes[ndx].setURL(url); }
void SSDPClass::setSerialNumber(uint8_t ndx, const char *serialNumber) { this->deviceTypes[ndx].setSerialNumber(serialNumber); }
//void SSDPClass::setSerialNumber(uint8_t ndx, const uint32_t serialNumber) { this->deviceTypes[ndx].setSerialNumber(serialNumber); }
void SSDPClass::setModelName(uint8_t ndx, const char *name) { this->deviceTypes[ndx].setModelName(name); }
void SSDPClass::setModelNumber(uint8_t ndx, const char *num) { this->deviceTypes[ndx].setModelNumber(num); }
void SSDPClass::setModelURL(uint8_t ndx, const char *url) { this->deviceTypes[ndx].setModelURL(url); }
void SSDPClass::setManufacturer(uint8_t ndx, const char *name) { this->deviceTypes[ndx].setManufacturer(name); }
void SSDPClass::setManufacturerURL(uint8_t ndx, const char *url) { this->deviceTypes[ndx].setManufacturerURL(url); }
void SSDPClass::setChipId(uint8_t ndx, uint32_t chipId) { this->deviceTypes[ndx].setChipId(chipId); }
#if !defined(NO_GLOBAL_INSTANCES) && !defined(NO_GLOBAL_SSDP)
SSDPClass SSDP;
#endif

172
SSDP.h Normal file
View file

@ -0,0 +1,172 @@
#ifndef SSDP_h
#define SSDP_h
#include <Arduino.h>
#include <WiFi.h>
#include <AsyncUDP.h>
#define SSDP_UUID_SIZE 42
#define SSDP_SCHEMA_URL_SIZE 64
#define SSDP_DEVICE_TYPE_SIZE 64
#define SSDP_FRIENDLY_NAME_SIZE 64
#define SSDP_SERIAL_NUMBER_SIZE 37
#define SSDP_PRESENTATION_URL_SIZE 64
#define SSDP_MODEL_NAME_SIZE 64
#define SSDP_MODEL_URL_SIZE 64
#define SSDP_MODEL_VERSION_SIZE 32
#define SSDP_MANUFACTURER_SIZE 64
#define SSDP_MANUFACTURER_URL_SIZE 64
#define SSDP_INTERVAL_SECONDS 1800
#define SSDP_MULTICAST_TTL 2
#define SSDP_HTTP_PORT 80
#define SSDP_CHILD_DEVICES 0
#define SSDP_QUEUE_SIZE 5
//#define DEBUG_SSDP Serial
//#define DEBUG_SSDP_PACKET Serial
typedef enum {
NONE,
SEARCH,
NOTIFY
} ssdp_method_t;
#define SSDP_FIELD_LEN 128
#define SSDP_LOCATION_LEN 256
typedef enum {
UNKNOWN,
MULTICAST,
UNICAST
} ssdp_req_types_t;
typedef struct ssdp_packet_t {
bool pending;
unsigned long recvd;
ssdp_method_t method;
char req [SSDP_FIELD_LEN];
char st [SSDP_FIELD_LEN];
char man [SSDP_FIELD_LEN];
char agent [SSDP_FIELD_LEN];
char host [SSDP_LOCATION_LEN];
uint8_t mx;
ssdp_req_types_t type;
bool valid;
};
class UPNPDeviceType {
char m_usn[SSDP_MANUFACTURER_URL_SIZE];
public:
UPNPDeviceType();
UPNPDeviceType(const char *deviceType);
UPNPDeviceType(const String& deviceType) { UPNPDeviceType(deviceType.c_str()); }
UPNPDeviceType(const String& deviceType, const String& uuid);
UPNPDeviceType(const char *deviceType, const char *uuid, const char *friendlyName);
UPNPDeviceType(const char *deviceType, const char *uuid);
UPNPDeviceType(const String& deviceType, const String& uuid, const String& friendlyName) { UPNPDeviceType(deviceType.c_str(), uuid.c_str(), friendlyName.c_str()); }
unsigned long lastNotified;
char schemaURL[SSDP_SCHEMA_URL_SIZE];
char uuid[SSDP_UUID_SIZE];
char deviceType[SSDP_DEVICE_TYPE_SIZE];
char friendlyName[SSDP_FRIENDLY_NAME_SIZE];
char serialNumber[SSDP_SERIAL_NUMBER_SIZE];
char presentationURL[SSDP_PRESENTATION_URL_SIZE];
char manufacturer[SSDP_MANUFACTURER_SIZE];
char manufacturerURL[SSDP_MANUFACTURER_URL_SIZE];
char modelName[SSDP_MODEL_NAME_SIZE];
char modelURL[SSDP_MODEL_URL_SIZE];
char modelNumber[SSDP_MODEL_VERSION_SIZE];
bool isActive;
void setSchemaURL(const char *url);
void setDeviceType(const char *dtype);
void setUUID(const char *id);
void setName(const char *name);
void setURL(const char *url);
void setSerialNumber(const char *sn);
void setSerialNumber(const uint32_t sn);
void setModelName(const char *name);
void setModelNumber(const char *num);
void setModelURL(const char *url);
void setManufacturer(const char *name);
void setManufacturerURL(const char *url);
//char *getUSN();
char *getUSN(const char *st);
void setChipId(uint32_t chipId);
};
typedef struct ssdp_response_t {
bool waiting;
IPAddress address;
uint16_t port;
UPNPDeviceType *dev;
bool sendUUID;
unsigned long sendTime;
char st[SSDP_DEVICE_TYPE_SIZE];
};
class SSDPClass {
uint8_t m_cdeviceTypes = SSDP_CHILD_DEVICES + 1;
protected:
ssdp_response_t sendQueue[SSDP_QUEUE_SIZE];
//ssdp_response_t sendQueue[SSDP_QUEUE_SIZE];
//void _send(ssdp_method_t method, UPNPDeviceType *dev, bool useUUID);
//void _sendAll(ssdp_method_t method, bool useUUID);
void _startTimer();
void _stopTimer();
void _sendNotify();
void _sendNotify(UPNPDeviceType *d);
void _sendNotify(UPNPDeviceType *d, bool root);
void _sendNotify(const char *);
void _sendByeBye();
void _sendByeBye(UPNPDeviceType *d);
void _sendByeBye(UPNPDeviceType *d, bool root);
void _sendByeBye(const char *);
void _sendQueuedResponses();
void _sendResponse(IPAddress addr, uint16_t port, UPNPDeviceType *d, char *st, bool sendUUID);
AsyncUDP _server;
hw_timer_t* _timer = nullptr;
uint16_t _port = SSDP_HTTP_PORT;
uint8_t _ttl = SSDP_MULTICAST_TTL;
uint32_t _interval = SSDP_INTERVAL_SECONDS;
void _processRequest(AsyncUDPPacket &p);
void _parsePacket(ssdp_packet_t *pkt, AsyncUDPPacket &p);
void _printPacket(ssdp_packet_t *pkt);
bool _startsWith(const char* pre, const char* str);
void _addToSendQueue(IPAddress addr, uint16_t port, UPNPDeviceType *d, char *st, uint8_t sec, bool sendUUID);
public:
SSDPClass();
~SSDPClass();
UPNPDeviceType deviceTypes[SSDP_CHILD_DEVICES + 1];
bool begin();
void loop();
void end();
bool isStarted = false;
IPAddress localIP();
UPNPDeviceType* getDeviceTypes(uint8_t ndx);
UPNPDeviceType* getDeviceType(uint8_t ndx);
UPNPDeviceType* findDeviceByType(char *devType);
UPNPDeviceType* findDeviceByUUID(char *uuid);
void setHTTPPort(uint16_t port);
void setTTL(uint8_t ttl);
void setInterval(uint32_t interval);
void schema(WiFiClient client) { schema((Print&)std::ref(client)); }
void schema(Print &print);
void setDeviceType(uint8_t ndx, UPNPDeviceType *dt);
void setDeviceType(uint8_t ndx, const String& type) { setDeviceType(ndx, type.c_str()); }
void setDeviceType(uint8_t ndx, const char *type);
void setUUID(uint8_t ndx, const char *uuid);
void setUUID(uint8_t ndx, const char *prefix, uint32_t id);
void setName(uint8_t ndx, const char *name);
void setURL(uint8_t ndx, const char *url);
void setSchemaURL(uint8_t ndx, const char *url);
void setSerialNumber(uint8_t ndx, const char *serialNumber);
void setModelName(uint8_t ndx, const char *name);
void setModelNumber(uint8_t ndx, const char *num);
void setModelURL(uint8_t ndx, const char *url);
void setManufacturer(uint8_t ndx, const char *name);
void setManufacturerURL(uint8_t ndx, const char *url);
void setActive(uint8_t ndx, bool bActive);
void setChipId(uint8_t ndx, uint32_t chipId);
};
#if !defined(NO_GLOBAL_INSTANCES) && !defined(NO_GLOBAL_SSSDP)
extern SSDPClass SSDP;
#endif
#endif

85
Sockets.cpp Normal file
View file

@ -0,0 +1,85 @@
#include <Arduino.h>
#include <ArduinoJson.h>
#include <WebSocketsServer.h>
#include "Sockets.h"
#include "ConfigSettings.h"
extern ConfigSettings settings;
WebSocketsServer sockServer = WebSocketsServer(8080);
char g_buffer[1024];
/*********************************************************************
* ClientSocketEvent class members
********************************************************************/
void ClientSocketEvent::prepareMessage(const char *evt, const char *payload) {
sprintf(this->msg, "42[%s,%s]", evt, payload);
}
/*********************************************************************
* SocketEmitter class members
********************************************************************/
void SocketEmitter::startup() {
}
void SocketEmitter::begin() {
sockServer.begin();
sockServer.onEvent(this->wsEvent);
}
void SocketEmitter::loop() {
sockServer.loop();
}
bool SocketEmitter::sendToClients(const char *evt, JsonObject &obj) {
serializeJson(obj, g_buffer, sizeof(g_buffer));
return this->sendToClients(evt, g_buffer);
}
bool SocketEmitter::sendToClient(uint8_t num, const char *evt, JsonObject &obj) {
serializeJson(obj, g_buffer, sizeof(g_buffer));
return this->sendToClient(num, evt, g_buffer);
}
bool SocketEmitter::sendToClients(const char *evt, const char *payload) {
if(settings.status == DS_FWUPDATE) return true;
this->evt.prepareMessage(evt, payload);
return sockServer.broadcastTXT(this->evt.msg);
}
bool SocketEmitter::sendToClient(uint8_t num, const char *evt, const char *payload) {
if(settings.status == DS_FWUPDATE) return true;
this->evt.prepareMessage(evt, payload);
return sockServer.sendTXT(num, this->evt.msg);
}
void SocketEmitter::end() { sockServer.close(); }
void SocketEmitter::disconnect() { sockServer.disconnect(); }
void SocketEmitter::wsEvent(uint8_t num, WStype_t type, uint8_t *payload, size_t length) {
switch(type) {
case WStype_DISCONNECTED:
Serial.printf("Socket [%u] Disconnected!\n", num);
break;
case WStype_CONNECTED:
{
IPAddress ip = sockServer.remoteIP(num);
Serial.printf("Socket [%u] Connected from %d.%d.%d.%d url: %s\n", num, ip[0], ip[1], ip[2], ip[3], payload);
// Send all the current Sensor readings to the client.
sockServer.sendTXT(num, "Connected");
settings.emitSockets();
//settings.Inputs.emitSocket(num);
}
break;
case WStype_TEXT:
Serial.printf("Socket [%u] get Text: %s\n", num, payload);
// send message to client
// webSocket.sendTXT(num, "message here");
// send data to all connected clients
// sockServer.broadcastTXT("message here");
break;
case WStype_BIN:
Serial.printf("[%u] get binary length: %u\n", num, length);
//hexdump(payload, length);
// send message to client
// sockServer.sendBIN(num, payload, length);
break;
}
}

24
Sockets.h Normal file
View file

@ -0,0 +1,24 @@
#include <WebSocketsServer.h>
#ifndef sockets_h
#define sockets_h
#include <ArduinoJson.h>
class ClientSocketEvent {
public:
char msg[1024];
void prepareMessage(const char *evt, const char *data);
};
class SocketEmitter {
ClientSocketEvent evt;
public:
void startup();
void begin();
void loop();
void end();
void disconnect();
bool sendToClients(const char *evt, const char *data);
bool sendToClient(uint8_t num, const char *evt, const char *data);
bool sendToClients(const char *evt, JsonObject &obj);
bool sendToClient(uint8_t num, const char *evt, JsonObject &obj);
static void wsEvent(uint8_t num, WStype_t type, uint8_t *payload, size_t length);
};
#endif

1237
Somfy.cpp Normal file

File diff suppressed because it is too large Load diff

206
Somfy.h Normal file
View file

@ -0,0 +1,206 @@
#ifndef SOMFY_H
#define SOMFY_H
#define SOMFY_MAX_SHADES 5
#define SOMFY_MAX_LINKED_REMOTES 2
enum class somfy_commands : byte {
My = 0x1,
Up = 0x2,
MyUp = 0x3,
Down = 0x4,
MyDown = 0x5,
UpDown = 0x6,
Prog = 0x8,
SunFlag = 0x9,
Flag = 0xA
};
String translateSomfyCommand(const somfy_commands cmd);
somfy_commands translateSomfyCommand(const String& string);
typedef struct somfy_frame_t {
int rssi = 0;
byte lqi = 0x0;
somfy_commands cmd;
uint32_t remoteAddress = 0;
uint16_t rollingCode = 0;
uint8_t encKey = 0;
uint8_t checksum = 0;
bool valid = false;
void print();
void encodeFrame(const uint32_t address, const somfy_commands cmd, const uint16_t rcode, byte* frame);
void decodeFrame(byte* frame);
};
class SomfyRemote {
// These sizes for the data have been
// confirmed. The address is actually 24bits
// and the rolling code is 16 bits.
protected:
char m_remotePrefId[10] = "";
uint32_t m_remoteAddress = 0;
void encodeFrame(byte *frame, somfy_commands cmd, uint16_t rcode);
void decodeFrame(byte *frame, somfy_frame_t *decoded);
void sendFrame(byte *frame, byte sync);
void sendHigh(uint16_t durationInMicroseconds);
void sendLow(uint16_t durationInMicroseconds);
public:
char *getRemotePrefId() {return m_remotePrefId;}
virtual bool toJSON(JsonObject &obj);
virtual void setRemoteAddress(uint32_t address);
virtual uint32_t getRemoteAddress();
virtual uint16_t getNextRollingCode();
virtual uint16_t setRollingCode(uint16_t code);
uint16_t lastRollingCode = 0;
void sendCommand(somfy_commands, uint8_t repeat = 4);
};
class SomfyLinkedRemote : public SomfyRemote {
public:
SomfyLinkedRemote();
};
class SomfyShade : public SomfyRemote {
protected:
uint8_t shadeId = 255;
uint64_t moveStart = 0;
float startPos = 0.0;
public:
void load();
float currentPos = 0.0;
//uint16_t movement = 0;
int8_t direction = 0; // 0 = stopped, 1=down, -1=up.
uint8_t position = 0;
uint8_t target = 0;
SomfyLinkedRemote linkedRemotes[SOMFY_MAX_LINKED_REMOTES];
bool paired = false;
bool fromJSON(JsonObject &obj);
bool toJSON(JsonObject &obj) override;
char name[20] = "";
void setShadeId(uint8_t id) { shadeId = id; }
uint8_t getShadeId() { return shadeId; }
uint16_t upTime = 10000;
uint16_t downTime = 1000;
bool save();
void checkMovement();
void processFrame(somfy_frame_t &frame);
void setMovement(int8_t dir);
bool linkRemote(uint32_t remoteAddress, uint16_t rollingCode = 0);
bool unlinkRemote(uint32_t remoteAddress);
void emitState();
void emitConfig();
void publish();
};
typedef struct transceiver_config_t {
bool printBuffer = false;
uint8_t type = 56; // 56 or 80 bit protocol.
uint8_t SCKPin = 18;
uint8_t TXPin = 6;
uint8_t RXPin = 4;
uint8_t MOSIPin = 23;
uint8_t MISOPin = 19;
uint8_t CSNPin = 5;
bool internalCCMode = false; // Use internal transmission mode FIFO buffers.
byte modulationMode = 2; // Modulation mode. 0 = 2-FSK, 1 = GFSK, 2 = ASK/OOK, 3 = 4-FSK, 4 = MSK.
float frequency = 433.42; // Basic frequency
float deviation = 47.60; // Set the Frequency deviation in kHz. Value from 1.58 to 380.85. Default is 47.60 kHz.
uint8_t channel = 0; // The channel number from 0 to 255
float channelSpacing = 199.95; // Channel spacing in multiplied by the channel number and added to the base frequency in kHz. 25.39 to 405.45. Default 199.95
float rxBandwidth = 812.5; // Receive bandwidth in kHz. Value from 58.03 to 812.50. Default is 99.97kHz.
float dataRate = 99.97; // The data rate in kBaud. 0.02 to 1621.83 Default is 99.97.
int8_t txPower = 12; // Transmission power {-30, -20, -15, -10, -6, 0, 5, 7, 10, 11, 12}. Default is 12.
uint8_t syncMode = 2; // 0=No preamble/sync,
// 1=16 sync word bits detected,
// 2=16/16 sync words bits detected.
// 3=30/32 sync word bits detected,
// 4=No preamble/sync carrier above threshold
// 5=15/16 + carrier above threshold.
// 6=16/16 + carrier-sense above threshold
// 7=0/32 + carrier-sense above threshold
uint16_t syncWordHigh = 211; // The sync word used to the sync mode.
uint16_t syncWordLow = 145; // The sync word used to the sync mode.
uint8_t addrCheckMode = 0; // 0=No address filtration
// 1=Check address without broadcast.
// 2=Address check with 0 as broadcast.
// 3=Address check with 0 or 255 as broadcast.
uint8_t checkAddr = 0; // Packet filter address depending on addrCheck settings.
bool dataWhitening = false; // Indicates whether data whitening should be applied.
uint8_t pktFormat = 0; // 0=Use FIFO buffers form RX and TX
// 1=Synchronous serial mode. RX on GDO0 and TX on either GDOx pins.
// 2=Random TX mode. Send data using PN9 generator.
// 3=Asynchronous serial mode. RX on GDO0 and TX on either GDOx pins.
uint8_t pktLengthMode = 0; // 0=Fixed packet length
// 1=Variable packet length
// 2=Infinite packet length
// 3=Reserved
uint8_t pktLength = 0; // Packet length
bool useCRC = false; // Indicates whether CRC is to be used.
bool autoFlushCRC = false; // Automatically flush RX FIFO when CRC fails. If more than one packet is in the buffer it too will be flushed.
bool disableDCFilter = false; // Digital blocking filter for demodulator. Only for data rates <= 250k.
bool enableManchester = true; // Enable/disable Manchester encoding.
bool enableFEC = false; // Enable/disable forward error correction.
uint8_t minPreambleBytes = 0; // The minimum number of preamble bytes to be transmitten.
// 0=2bytes
// 1=3bytes
// 2=4bytes
// 3=6bytes
// 4=8bytes
// 5=12bytes
// 6=16bytes
// 7=24bytes
uint8_t pqtThreshold = 0; // Preamble quality estimator threshold. The preable quality estimator increase an internal counter by one each time a bit is received that is different than the prevoius bit and
// decreases the bounter by 8 each time a bit is received that is the same as the lats bit. A threshold of 4 PQT for this counter is used to gate sync word detection.
// When PQT = 0 a sync word is always accepted.
bool appendStatus = false; // Appends the RSSI and LQI values to the TX packed as well as the CRC.
void fromJSON(JsonObject& obj);
void toJSON(JsonObject& obj);
void save();
void load();
void apply();
};
class Transceiver {
private:
static void handleReceive();
bool _received = false;
somfy_frame_t frame;
public:
transceiver_config_t config;
bool printBuffer = false;
bool toJSON(JsonObject& obj);
bool fromJSON(JsonObject& obj);
bool save();
bool begin();
void loop();
bool end();
bool receive();
void clearReceived();
void enableReceive();
void disableReceive();
somfy_frame_t& lastFrame();
void beginTransmit();
void endTransmit();
};
class SomfyShadeController {
protected:
uint8_t m_shadeIds[SOMFY_MAX_SHADES];
uint8_t getNextShadeId();
public:
uint32_t startingAddress;
SomfyShadeController();
Transceiver transceiver;
SomfyShade *addShade();
bool deleteShade(uint8_t shadeId);
bool begin();
void loop();
void end();
SomfyShade shades[SOMFY_MAX_SHADES];
bool toJSON(DynamicJsonDocument &doc);
bool toJSON(JsonObject &obj);
uint8_t shadeCount();
SomfyShade * getShadeById(uint8_t shadeId);
SomfyShade * findShadeByRemoteAddress(uint32_t address);
void processFrame(somfy_frame_t &frame);
void publish();
};
#endif

54
SomfyController.ino Normal file
View file

@ -0,0 +1,54 @@
#include <WiFi.h>
#include <LittleFS.h>
#include "ConfigSettings.h"
#include "Network.h"
#include "Web.h"
#include "Sockets.h"
#include "Utils.h"
#include "Somfy.h"
#include "MQTT.h"
ConfigSettings settings;
Web webServer;
SocketEmitter sockEmit;
Network net;
rebootDelay_t rebootDelay;
SomfyShadeController somfy;
MQTTClass mqtt;
void setup() {
Serial.begin(115200);
Serial.println();
Serial.println("Startup/Boot....");
settings.begin();
WiFi.persistent(false);
Serial.print("WiFi Mode: ");
Serial.println(WiFi.getMode());
Serial.println("Mounting File System...");
if(LittleFS.begin()) Serial.println("File system mounted successfully");
else Serial.println("Error mounting file system");
if(WiFi.status() == WL_CONNECTED) WiFi.disconnect(true);
WiFi.mode(WIFI_AP_STA);
delay(10);
Serial.println();
webServer.startup();
webServer.begin();
delay(1000);
net.setup();
somfy.begin();
}
void loop() {
// put your main code here, to run repeatedly:
if(rebootDelay.reboot && millis() > rebootDelay.rebootTime) ESP.restart();
net.loop();
somfy.loop();
if(WiFi.status() == WL_CONNECTED) {
webServer.loop();
sockEmit.loop();
}
if(rebootDelay.reboot && millis() > rebootDelay.rebootTime) {
net.end();
ESP.restart();
}
}

Binary file not shown.

44
Utils.cpp Normal file
View file

@ -0,0 +1,44 @@
#include <Arduino.h>
#include <time.h>
#include "Utils.h"
/*********************************************************************
* Timestamp class members
********************************************************************/
time_t Timestamp::getUTC() {
time_t t;
time(&t);
return t;
}
time_t Timestamp::getUTC(time_t t) {
tm tmUTC;
gmtime_r(&t, &tmUTC);
return mktime(&tmUTC);
}
char * Timestamp::getISOTime() { return this->getISOTime(this->getUTC()); }
char * Timestamp::getISOTime(time_t epoch) {
struct tm *dt = localtime((time_t *)&epoch);
return this->formatISO(dt, this->tzOffset());
}
char * Timestamp::formatISO(struct tm *dt, int tz) {
int tzHrs = floor(tz/100);
int tzMin = tz - (tzHrs * 100);
int ms = millis() % 1000;
char isoTime[32];
snprintf(this->_timeBuffer, sizeof(this->_timeBuffer), "%04d-%02d-%02dT%02d:%02d:%02d.%03d%s%02d%02d",
dt->tm_year + 1900, dt->tm_mon + 1, dt->tm_mday, dt->tm_hour, dt->tm_min, dt->tm_sec, ms, tzHrs < 0 ? "-" : "+", abs(tzHrs), abs(tzMin));
return this->_timeBuffer;
}
int Timestamp::tzOffset() {
time_t now;
time(&now);
tm tmLocal, tmUTC;
gmtime_r(&now, &tmUTC);
localtime_r(&now, &tmLocal);
long diff = mktime(&tmLocal) - mktime(&tmUTC);
if(tmLocal.tm_isdst) diff += 3600;
int hrs = (int)((diff/3600) * 100);
int mins = diff - (hrs * 36);
return hrs + mins;
}

88
Utils.h Normal file
View file

@ -0,0 +1,88 @@
#ifndef utils_h
#define utils_h
#ifndef LED_BUILTIN
#define LED_BUILTIN 2
#endif
#ifndef D3
#define D3 3
#endif
#ifndef D0
#define D0 0
#endif
static void SETCHARPROP(char *prop, const char *value, size_t size) {strncpy(prop, value, size); prop[size - 1] = '\0';}
namespace util {
// Createa a custom to_string function. C++ can be annoying
// with all the trailing 0s on number formats.
template <typename T> std::string to_string(const T& t) {
std::string str{std::to_string (t)};
int offset{1};
if (str.find_last_not_of('0') == str.find('.')) {
offset = 0;
}
str.erase ( str.find_last_not_of('0') + 1, std::string::npos );
str.erase ( str.find_last_not_of('.') + 1, std::string::npos );
return str;
}
}
static void _ltrim(char *str) {
int s = 0, j, k = 0;
int e = strlen(str);
while(s < e && (str[s] == ' ' || str[s] == '\n' || str[s] == '\r' || str[s] == '\t' || str[s] == '"')) s++;
if(s > 0) {
for(j = s; j < e; j++) {
str[k] = str[j];
k++;
}
str[k] = '\0';
}
//if(s > 0) strcpy(str, &str[s]);
}
static void _rtrim(char *str) {
int e = strlen(str) - 1;
while(e >= 0 && (str[e] == ' ' || str[e] == '\n' || str[e] == '\r' || str[e] == '\t' || str[e] == '"')) {str[e] = '\0'; e--;}
}
static void _trim(char *str) { _ltrim(str); _rtrim(str); }
typedef struct rebootDelay_t {
bool reboot = false;
int rebootTime = 0;
bool closed = false;
};
class Timestamp {
char _timeBuffer[44];
public:
time_t getUTC();
time_t getUTC(time_t epoch);
char * getISOTime();
char * getISOTime(time_t epoch);
char * formatISO(struct tm *dt, int tz);
int tzOffset();
};
// Sort an array
template<typename AnyType> void sortArray(AnyType array[], size_t sizeOfArray);
// Sort in reverse
template<typename AnyType> void sortArrayReverse(AnyType array[], size_t sizeOfArray);
// Sort an array with custom comparison function
template<typename AnyType> void sortArray(AnyType array[], size_t sizeOfArray, bool (*largerThan)(AnyType, AnyType));
// Sort in reverse with custom comparison function
template<typename AnyType> void sortArrayReverse(AnyType array[], size_t sizeOfArray, bool (*largerThan)(AnyType, AnyType));
namespace ArduinoSort {
template<typename AnyType> bool builtinLargerThan(AnyType first, AnyType second) { return first > second; }
//template<> bool builtinLargerThan(char* first, char* second) { return strcmp(first, second) > 0; }
template<typename AnyType> void insertionSort(AnyType array[], size_t sizeOfArray, bool reverse, bool (*largerThan)(AnyType, AnyType)) { for (size_t i = 1; i < sizeOfArray; i++) {
for (size_t j = i; j > 0 && (largerThan(array[j-1], array[j]) != reverse); j--) {
AnyType tmp = array[j-1];
array[j-1] = array[j];
array[j] = tmp;
}
}
}
}
template<typename AnyType> void sortArray(AnyType array[], size_t sizeOfArray) { ArduinoSort::insertionSort(array, sizeOfArray, false, ArduinoSort::builtinLargerThan); }
template<typename AnyType> void sortArrayReverse(AnyType array[], size_t sizeOfArray) { ArduinoSort::insertionSort(array, sizeOfArray, true, ArduinoSort::builtinLargerThan); }
template<typename AnyType> void sortArray(AnyType array[], size_t sizeOfArray, bool (*largerThan)(AnyType, AnyType)) { ArduinoSort::insertionSort(array, sizeOfArray, false, largerThan); }
template<typename AnyType> void sortArrayReverse(AnyType array[], size_t sizeOfArray, bool (*largerThan)(AnyType, AnyType)) { ArduinoSort::insertionSort(array, sizeOfArray, true, largerThan); }
#endif

743
Web.cpp Normal file
View file

@ -0,0 +1,743 @@
#include <Arduino.h>
#include <WiFi.h>
#include <WebServer.h>
#include <LittleFS.h>
#include <Update.h>
#include "ConfigSettings.h"
#include "Web.h"
#include "Utils.h"
#include "SSDP.h"
#include "Somfy.h"
extern ConfigSettings settings;
extern SSDPClass SSDP;
extern rebootDelay_t rebootDelay;
extern SomfyShadeController somfy;
extern Web webServer;
#define WEB_MAX_RESPONSE 2048
static char g_content[WEB_MAX_RESPONSE];
// General responses
static const char _response_404[] = "404: Not Found";
// Encodings
static const char _encoding_text[] = "text/plain";
static const char _encoding_html[] = "text/html";
static const char _encoding_json[] = "application/json";
WebServer server(80);
void Web::startup() {
Serial.println("Launching web server...");
}
void Web::loop() {
server.handleClient();
}
void Web::sendCORSHeaders() {
//server.sendHeader(F("Access-Control-Allow-Origin"), F("*"));
//server.sendHeader(F("Access-Control-Max-Age"), F("600"));
//server.sendHeader(F("Access-Control-Allow-Methods"), F("PUT,POST,GET,OPTIONS"));
//server.sendHeader(F("Access-Control-Allow-Headers"), F("*"));
}
void Web::end() {
//server.end();
}
void Web::begin() {
Serial.println("Creating Web MicroServices...");
server.enableCORS(true);
server.on("/upnp.xml", []() {
SSDP.schema(server.client());
});
server.on("/", []() {
webServer.sendCORSHeaders();
int statusCode = 200;
// Load the index html page from the data directory.
Serial.println("Loading file index.html");
File file = LittleFS.open("/index.html", "r");
if(!file) {
Serial.println("Error opening data/index.html");
server.send(500, _encoding_html, "Unable to open data/index.html");
}
server.streamFile(file, _encoding_html);
file.close();
});
server.on("/configRadio", []() {
webServer.sendCORSHeaders();
// Load the index html page from the data directory.
Serial.println("Loading file configRadio.html");
File file = LittleFS.open("/configRadio.html", "r");
if(!file) {
Serial.println("Error opening configRadio.html");
server.send(500, _encoding_text, "configRadio.html");
}
server.streamFile(file, _encoding_html);
file.close();
});
server.on("/main.css", []() {
webServer.sendCORSHeaders();
// Load the index html page from the data directory.
Serial.println("Loading file main.css");
File file = LittleFS.open("/main.css", "r");
if(!file) {
Serial.println("Error opening data/main.css");
server.send(500, _encoding_text, "Unable to open data/main.css");
}
server.streamFile(file, "text/css");
file.close();
});
server.on("/icons.css", []() {
webServer.sendCORSHeaders();
// Load the index html page from the data directory.
Serial.println("Loading file icons.css");
File file = LittleFS.open("/icons.css", "r");
if(!file) {
Serial.println("Error opening data/icons.css");
server.send(500, _encoding_text, "Unable to open data/icons.css");
}
server.streamFile(file, "text/css");
file.close();
});
server.onNotFound([]() { server.send(404, _encoding_text, _response_404); });
server.on("/somfyController", []() {
webServer.sendCORSHeaders();
HTTPMethod method = server.method();
if(method == HTTP_POST || method == HTTP_GET) {
Serial.println("Begin Serialize Somfy...");
DynamicJsonDocument doc(2048);
somfy.toJSON(doc);
serializeJson(doc, g_content);
server.send(200, _encoding_json, g_content);
}
else server.send(404, _encoding_text, _response_404);
});
server.on("/addShade", []() {
HTTPMethod method = server.method();
SomfyShade *shade;
if(method == HTTP_POST || method == HTTP_PUT) {
Serial.println("Adding a shade");
DynamicJsonDocument doc(256);
DeserializationError err = deserializeJson(doc, server.arg("plain"));
if(err) {
switch(err.code()) {
case DeserializationError::InvalidInput:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Invalid JSON payload\"}"));
break;
case DeserializationError::NoMemory:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Out of memory parsing JSON\"}"));
break;
default:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"General JSON Deserialization failed\"}"));
break;
}
}
else {
Serial.println("Convering to JsonObject");
JsonObject obj = doc.as<JsonObject>();
Serial.println("Counting shades");
if(somfy.shadeCount() > SOMFY_MAX_SHADES) {
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Maximum number of shades exceeded.\"}"));
}
else {
Serial.println("Adding shade");
shade = somfy.addShade();
if(shade) {
Serial.println("Persisting toJSON");
shade->fromJSON(obj);
Serial.println("Saving to Preferences");
shade->save();
DynamicJsonDocument sdoc(256);
JsonObject sobj = sdoc.to<JsonObject>();
shade->toJSON(sobj);
serializeJson(sdoc, g_content);
server.send(200, _encoding_json, g_content);
}
else {
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Max number of shades added.\"}"));
}
}
}
}
if(shade) {
Serial.println("Serializing shade");
DynamicJsonDocument doc(256);
JsonObject obj = doc.to<JsonObject>();
shade->toJSON(obj);
serializeJson(doc, g_content);
Serial.println(g_content);
server.send(200, _encoding_json, g_content);
}
else {
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Error saving Somfy Shade.\"}"));
}
});
server.on("/shade", []() {
webServer.sendCORSHeaders();
HTTPMethod method = server.method();
if(method == HTTP_GET) {
if(server.hasArg("shadeId")) {
int shadeId = atoi(server.arg("shadeId").c_str());
SomfyShade *shade = somfy.getShadeById(shadeId);
if(shade) {
DynamicJsonDocument doc(256);
JsonObject obj = doc.to<JsonObject>();
shade->toJSON(obj);
serializeJson(doc, g_content);
server.send(200, _encoding_json, g_content);
}
else server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Shade Id not found.\"}"));
}
else {
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"You must supply a valid shade id.\"}"));
}
}
else if(method == HTTP_PUT || method == HTTP_POST) {
// We are updating an existing shade.
if(server.hasArg("plain")) {
Serial.println("Updating a shade");
DynamicJsonDocument doc(256);
DeserializationError err = deserializeJson(doc, server.arg("plain"));
if(err) {
switch(err.code()) {
case DeserializationError::InvalidInput:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Invalid JSON payload\"}"));
break;
case DeserializationError::NoMemory:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Out of memory parsing JSON\"}"));
break;
default:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"General JSON Deserialization failed\"}"));
break;
}
}
else {
JsonObject obj = doc.as<JsonObject>();
if(obj.containsKey("shadeId")) {
SomfyShade *shade = somfy.getShadeById(obj["shadeId"]);
if(shade) {
shade->fromJSON(obj);
shade->save();
DynamicJsonDocument sdoc(256);
JsonObject sobj = sdoc.to<JsonObject>();
shade->toJSON(sobj);
serializeJson(sdoc, g_content);
server.send(200, _encoding_json, g_content);
}
else server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Shade Id not found.\"}"));
}
else server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"No shade id was supplied.\"}"));
}
}
else server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"No shade object supplied.\"}"));
}
});
server.on("/saveShade", []() {
webServer.sendCORSHeaders();
HTTPMethod method = server.method();
if(method == HTTP_PUT || method == HTTP_POST) {
// We are updating an existing shade.
if(server.hasArg("plain")) {
Serial.println("Updating a shade");
DynamicJsonDocument doc(256);
DeserializationError err = deserializeJson(doc, server.arg("plain"));
if(err) {
switch(err.code()) {
case DeserializationError::InvalidInput:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Invalid JSON payload\"}"));
break;
case DeserializationError::NoMemory:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Out of memory parsing JSON\"}"));
break;
default:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"General JSON Deserialization failed\"}"));
break;
}
}
else {
JsonObject obj = doc.as<JsonObject>();
if(obj.containsKey("shadeId")) {
SomfyShade *shade = somfy.getShadeById(obj["shadeId"]);
if(shade) {
shade->fromJSON(obj);
shade->save();
DynamicJsonDocument sdoc(256);
JsonObject sobj = sdoc.to<JsonObject>();
shade->toJSON(sobj);
serializeJson(sdoc, g_content);
server.send(200, _encoding_json, g_content);
}
else server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Shade Id not found.\"}"));
}
else server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"No shade id was supplied.\"}"));
}
}
else server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"No shade object supplied.\"}"));
}
});
server.on("/unlinkRemote", []() {
webServer.sendCORSHeaders();
HTTPMethod method = server.method();
if(method == HTTP_PUT || method == HTTP_POST) {
// We are updating an existing shade by adding a linked remote.
if(server.hasArg("plain")) {
DynamicJsonDocument doc(256);
DeserializationError err = deserializeJson(doc, server.arg("plain"));
if(err) {
switch(err.code()) {
case DeserializationError::InvalidInput:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Invalid JSON payload\"}"));
break;
case DeserializationError::NoMemory:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Out of memory parsing JSON\"}"));
break;
default:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"General JSON Deserialization failed\"}"));
break;
}
}
else {
JsonObject obj = doc.as<JsonObject>();
if(obj.containsKey("shadeId")) {
SomfyShade *shade = somfy.getShadeById(obj["shadeId"]);
if(shade) {
if(obj.containsKey("remoteAddress")) {
shade->unlinkRemote(obj["remoteAddress"]);
}
else {
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Remote address not provided.\"}"));
}
DynamicJsonDocument sdoc(256);
JsonObject sobj = sdoc.to<JsonObject>();
shade->toJSON(sobj);
serializeJson(sdoc, g_content);
server.send(200, _encoding_json, g_content);
}
else server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Shade Id not found.\"}"));
}
else server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"No shade id was supplied.\"}"));
}
}
else server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"No remote object supplied.\"}"));
}
});
server.on("/linkRemote", []() {
webServer.sendCORSHeaders();
HTTPMethod method = server.method();
if(method == HTTP_PUT || method == HTTP_POST) {
// We are updating an existing shade by adding a linked remote.
if(server.hasArg("plain")) {
Serial.println("Linking a remote");
DynamicJsonDocument doc(256);
DeserializationError err = deserializeJson(doc, server.arg("plain"));
if(err) {
switch(err.code()) {
case DeserializationError::InvalidInput:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Invalid JSON payload\"}"));
break;
case DeserializationError::NoMemory:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Out of memory parsing JSON\"}"));
break;
default:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"General JSON Deserialization failed\"}"));
break;
}
}
else {
JsonObject obj = doc.as<JsonObject>();
if(obj.containsKey("shadeId")) {
SomfyShade *shade = somfy.getShadeById(obj["shadeId"]);
if(shade) {
if(obj.containsKey("remoteAddress")) {
if(obj.containsKey("rollingCode")) shade->linkRemote(obj["remoteAddress"], obj["rollingCode"]);
else shade->linkRemote(obj["remoteAddress"]);
}
else {
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Remote address not provided.\"}"));
}
DynamicJsonDocument sdoc(256);
JsonObject sobj = sdoc.to<JsonObject>();
shade->toJSON(sobj);
serializeJson(sdoc, g_content);
server.send(200, _encoding_json, g_content);
}
else server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Shade Id not found.\"}"));
}
else server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"No shade id was supplied.\"}"));
}
}
else server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"No remote object supplied.\"}"));
}
});
server.on("/deleteShade", []() {
webServer.sendCORSHeaders();
HTTPMethod method = server.method();
uint8_t shadeId = 255;
if(method == HTTP_GET || method == HTTP_PUT || method == HTTP_POST) {
if(server.hasArg("shadeId")) {
shadeId = atoi(server.arg("shadeId").c_str());
}
else if(server.hasArg("plain")) {
Serial.println("Deleting a shade");
DynamicJsonDocument doc(256);
DeserializationError err = deserializeJson(doc, server.arg("plain"));
if(err) {
switch(err.code()) {
case DeserializationError::InvalidInput:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Invalid JSON payload\"}"));
break;
case DeserializationError::NoMemory:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Out of memory parsing JSON\"}"));
break;
default:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"General JSON Deserialization failed\"}"));
break;
}
}
else {
JsonObject obj = doc.as<JsonObject>();
if(obj.containsKey("shadeId")) shadeId = obj["shadeId"];//obj.getMember("shadeId").as<uint8_t>();
else server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"No shade id was supplied.\"}"));
}
}
else server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"No shade object supplied.\"}"));
}
SomfyShade *shade = somfy.getShadeById(shadeId);
if(!shade) server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Shade with the specified id not found.\"}"));
else {
somfy.deleteShade(shadeId);
server.send(200, _encoding_json, F("{\"status\":\"SUCCESS\",\"desc\":\"Shade deleted.\"}"));
}
});
server.on("/updateFirmware", HTTP_POST, []() {
webServer.sendCORSHeaders();
if(Update.hasError())
server.send(500, _encoding_json, "{\"status\":\"ERROR\",\"desc\":\"Error updating firmware: \"}");
else
server.send(200, _encoding_json, "{\"status\":\"ERROR\",\"desc\":\"Updating firmware: \"}");
rebootDelay.reboot = true;
rebootDelay.rebootTime = millis() + 500;
}, []() {
HTTPUpload& upload = server.upload();
if (upload.status == UPLOAD_FILE_START) {
Serial.printf("Update: %s\n", upload.filename.c_str());
if (!Update.begin(UPDATE_SIZE_UNKNOWN)) { //start with max available size
Update.printError(Serial);
}
} else if (upload.status == UPLOAD_FILE_WRITE) {
/* flashing firmware to ESP*/
if (Update.write(upload.buf, upload.currentSize) != upload.currentSize) {
Update.printError(Serial);
}
} else if (upload.status == UPLOAD_FILE_END) {
if (Update.end(true)) { //true to set the size to the current progress
Serial.printf("Update Success: %u\nRebooting...\n", upload.totalSize);
} else {
Update.printError(Serial);
}
}
});
server.on("/updateApplication", HTTP_POST, []() {
webServer.sendCORSHeaders();
server.sendHeader("Connection", "close");
server.send(200, _encoding_json, "{\"status\":\"ERROR\",\"desc\":\"Updating Application: \"}");
rebootDelay.reboot = true;
rebootDelay.rebootTime = millis() + 500;
}, []() {
HTTPUpload& upload = server.upload();
if (upload.status == UPLOAD_FILE_START) {
Serial.printf("Update: %s\n", upload.filename.c_str());
if (!Update.begin(UPDATE_SIZE_UNKNOWN, U_SPIFFS)) { //start with max available size and tell it we are updating the file system.
Update.printError(Serial);
}
} else if (upload.status == UPLOAD_FILE_WRITE) {
/* flashing firmware to ESP*/
if (Update.write(upload.buf, upload.currentSize) != upload.currentSize) {
Update.printError(Serial);
}
} else if (upload.status == UPLOAD_FILE_END) {
if (Update.end(true)) { //true to set the size to the current progress
Serial.printf("Update Success: %u\nRebooting...\n", upload.totalSize);
} else {
Update.printError(Serial);
}
}
});
server.on("/scanaps", []() {
webServer.sendCORSHeaders();
int statusCode = 200;
int n = WiFi.scanNetworks();
Serial.print("Scanned ");
Serial.print(n);
Serial.println(" networks");
String content = "{\"connected\": {\"name\":\"" + String(settings.WIFI.ssid) + "\",\"passphrase\":\"" + String(settings.WIFI.passphrase) + "\"}, \"accessPoints\":[";
for(int i = 0; i < n; ++i) {
if(i != 0) content += ",";
content += "{\"name\":\"" + WiFi.SSID(i) + "\",\"channel\":" + WiFi.channel(i) + ",\"encryption\":\"" + settings.WIFI.mapEncryptionType(WiFi.encryptionType(i)) + "\",\"strength\":" + WiFi.RSSI(i) + ",\"macAddress\":\"" + WiFi.BSSIDstr(i) + "\"}";
delay(10);
}
content += "]}";
server.send(statusCode, "application/json", content);
});
server.on("/reboot", []() {
webServer.sendCORSHeaders();
HTTPMethod method = server.method();
if(method == HTTP_POST || method == HTTP_PUT) {
Serial.println("Rebooting ESP...");
rebootDelay.reboot = true;
rebootDelay.rebootTime = millis() + 500;
server.send(200, "application/json", "{\"status\":\"OK\",\"desc\":\"Successfully started reboot\"}");
}
else {
server.send(201, _encoding_json, "{\"status\":\"ERROR\",\"desc\":\"Invalid HTTP Method: \"}");
}
});
server.on("/saveRadio", []() {
webServer.sendCORSHeaders();
DynamicJsonDocument doc(512);
DeserializationError err = deserializeJson(doc, server.arg("plain"));
if(err) {
Serial.print("Error parsing JSON ");
Serial.println(err.c_str());
String msg = err.c_str();
server.send(400, _encoding_html, "Error parsing JSON body<br>" + msg);
}
else {
JsonObject obj = doc.as<JsonObject>();
HTTPMethod method = server.method();
if(method == HTTP_POST || method == HTTP_PUT) {
somfy.transceiver.fromJSON(obj);
somfy.transceiver.save();
DynamicJsonDocument sdoc(512);
JsonObject sobj = sdoc.to<JsonObject>();
somfy.transceiver.toJSON(sobj);
serializeJson(sdoc, g_content);
server.send(200, _encoding_json, g_content);
//server.send(200, "application/json", "{\"status\":\"OK\",\"desc\":\"Successfully saved radio\"}");
}
else {
server.send(201, "application/json", "{\"status\":\"ERROR\",\"desc\":\"Invalid HTTP Method: \"}");
}
}
});
server.on("/getRadio", []() {
webServer.sendCORSHeaders();
DynamicJsonDocument doc(1024);
JsonObject obj = doc.to<JsonObject>();
somfy.transceiver.toJSON(obj);
serializeJson(doc, g_content);
server.send(200, _encoding_json, g_content);
});
/* THE Following endpoints have been deprecated now that I now can tune the radio settings without hacking around. The relevant settings
* have been included when the transceiver is saved.
server.on("/setRadioConfig", []() {
webServer.sendCORSHeaders();
DynamicJsonDocument doc(1280);
DeserializationError err = deserializeJson(doc, server.arg("plain"));
if(err) {
Serial.print("Error parsing JSON ");
Serial.println(err.c_str());
String msg = err.c_str();
server.send(400, _encoding_html, "Error parsing JSON body<br>" + msg);
}
else {
JsonObject obj = doc.as<JsonObject>();
transceiver_config_t cfg;
cfg.fromJSON(obj);
cfg.save();
cfg.apply();
serializeJson(doc, g_content);
server.send(200, _encoding_json, g_content);
}
});
server.on("/getRadioConfig", []() {
webServer.sendCORSHeaders();
DynamicJsonDocument doc(1024);
JsonObject obj = doc.to<JsonObject>();
transceiver_config_t cfg;
cfg.load();
cfg.toJSON(obj);
serializeJson(doc, g_content);
server.send(200, _encoding_json, g_content);
});
*/
server.on("/sendShadeCommand", [](){
server.sendHeader("Access-Control-Allow-Origin", "*");
HTTPMethod method = server.method();
uint8_t shadeId = 255;
somfy_commands command = somfy_commands::My;
if(method == HTTP_GET || method == HTTP_PUT || method == HTTP_POST) {
if(server.hasArg("shadeId")) {
shadeId = atoi(server.arg("shadeId").c_str());
if(server.hasArg("command")) command = translateSomfyCommand(server.arg("command"));
}
else if(server.hasArg("plain")) {
Serial.println("Sending Shade Command");
DynamicJsonDocument doc(256);
DeserializationError err = deserializeJson(doc, server.arg("plain"));
if(err) {
switch(err.code()) {
case DeserializationError::InvalidInput:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Invalid JSON payload\"}"));
break;
case DeserializationError::NoMemory:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Out of memory parsing JSON\"}"));
break;
default:
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"General JSON Deserialization failed\"}"));
break;
}
}
else {
JsonObject obj = doc.as<JsonObject>();
if(obj.containsKey("shadeId")) shadeId = obj["shadeId"];
else server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"No shade id was supplied.\"}"));
if(obj.containsKey("command")) {
String scmd = obj["command"];
command = translateSomfyCommand(scmd);
}
}
}
else server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"No shade object supplied.\"}"));
}
SomfyShade *shade = somfy.getShadeById(shadeId);
if(shade) {
// Send the command to the shade.
shade->sendCommand(command);
DynamicJsonDocument sdoc(256);
JsonObject sobj = sdoc.to<JsonObject>();
shade->toJSON(sobj);
serializeJson(sdoc, g_content);
server.send(200, _encoding_json, g_content);
}
else {
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Shade with the specified id not found.\"}"));
}
});
server.on("/setgeneral", []() {
webServer.sendCORSHeaders();
int statusCode = 200;
DynamicJsonDocument doc(256);
DeserializationError err = deserializeJson(doc, server.arg("plain"));
if(err) {
Serial.print("Error parsing JSON ");
Serial.println(err.c_str());
String msg = err.c_str();
server.send(400, _encoding_html, "Error parsing JSON body<br>" + msg);
}
else {
JsonObject obj = doc.as<JsonObject>();
HTTPMethod method = server.method();
if(method == HTTP_POST || method == HTTP_PUT) {
// Parse out all the inputs.
if(obj.containsKey("hostname")) {
settings.WIFI.fromJSON(obj);
settings.WIFI.save();
}
if(obj.containsKey("ntpServer") || obj.containsKey("ntpServer")) {
settings.NTP.fromJSON(obj);
settings.NTP.save();
}
server.send(200, "application/json", "{\"status\":\"OK\",\"desc\":\"Successfully set General Settings\"}");
}
else {
server.send(201, "application/json", "{\"status\":\"ERROR\",\"desc\":\"Invalid HTTP Method: \"}");
}
}
});
server.on("/connectwifi", []() {
webServer.sendCORSHeaders();
int statusCode = 200;
Serial.println("Settings WIFI connection...");
DynamicJsonDocument doc(512);
DeserializationError err = deserializeJson(doc, server.arg("plain"));
if(err) {
Serial.print("Error parsing JSON ");
Serial.println(err.c_str());
String msg = err.c_str();
server.send(400, "text/html", "Error parsing JSON body<br>" + msg);
}
else {
JsonObject obj = doc.as<JsonObject>();
HTTPMethod method = server.method();
//Serial.print(F("HTTP Method: "));
//Serial.println(server.method());
if(method == HTTP_POST || method == HTTP_PUT) {
String ssid = "";
String passphrase = "";
if(obj.containsKey("ssid")) ssid = obj["ssid"].as<String>();
if(obj.containsKey("passphrase")) passphrase = obj["passphrase"].as<String>();
bool reboot;
if(ssid.compareTo(settings.WIFI.ssid) != 0) reboot = true;
if(passphrase.compareTo(settings.WIFI.passphrase) != 0) reboot = true;
if(!settings.WIFI.ssidExists(ssid.c_str())) {
server.send(400, _encoding_json, "{\"status\":\"ERROR\",\"desc\":\"WiFi Network Does not exist\"}");
}
else {
SETCHARPROP(settings.WIFI.ssid, ssid.c_str(), sizeof(settings.WIFI.ssid));
SETCHARPROP(settings.WIFI.passphrase, passphrase.c_str(), sizeof(settings.WIFI.passphrase));
if(obj.containsKey("ssdpBroadcast")) settings.WIFI.ssdpBroadcast = obj["ssdpBroadcast"].as<bool>();
settings.WIFI.save();
settings.WIFI.print();
server.send(201, _encoding_json, "{\"status\":\"OK\",\"desc\":\"Successfully set server connection\"}");
if(reboot) {
Serial.println("Rebooting ESP for new WiFi settings...");
rebootDelay.reboot = true;
rebootDelay.rebootTime = millis() + 1000;
}
}
}
else {
server.send(201, _encoding_json, "{\"status\":\"ERROR\",\"desc\":\"Invalid HTTP Method: \"}");
}
}
});
server.on("/modulesettings", []() {
webServer.sendCORSHeaders();
DynamicJsonDocument doc(512);
JsonObject obj = doc.to<JsonObject>();
doc["fwVersion"] = settings.fwVersion;
settings.WIFI.toJSON(obj);
settings.NTP.toJSON(obj);
serializeJson(doc, g_content);
server.send(200, _encoding_json, g_content);
});
server.on("/connectmqtt", []() {
DynamicJsonDocument doc(512);
DeserializationError err = deserializeJson(doc, server.arg("plain"));
if(err) {
Serial.print("Error parsing JSON ");
Serial.println(err.c_str());
String msg = err.c_str();
server.send(400, F("text/html"), "Error parsing JSON body<br>" + msg);
}
else {
JsonObject obj = doc.as<JsonObject>();
HTTPMethod method = server.method();
Serial.print(F("HTTP Method: "));
Serial.println(server.method());
if(method == HTTP_POST || method == HTTP_PUT) {
settings.MQTT.fromJSON(obj);
settings.MQTT.save();
StaticJsonDocument<512> sdoc;
JsonObject sobj = sdoc.to<JsonObject>();
settings.MQTT.toJSON(sobj);
serializeJson(sdoc, g_content);
server.send(200, _encoding_json, g_content);
}
else {
server.send(201, "application/json", "{\"status\":\"ERROR\",\"desc\":\"Invalid HTTP Method: \"}");
}
}
});
server.on("/mqttsettings", []() {
webServer.sendCORSHeaders();
DynamicJsonDocument doc(512);
JsonObject obj = doc.to<JsonObject>();
settings.MQTT.toJSON(obj);
serializeJson(doc, g_content);
server.send(200, _encoding_json, g_content);
});
server.begin();
}

11
Web.h Normal file
View file

@ -0,0 +1,11 @@
#ifndef webserver_h
#define webserver_h
class Web {
public:
void sendCORSHeaders();
void startup();
void begin();
void loop();
void end();
};
#endif

396
data/configRadio.html Normal file
View file

@ -0,0 +1,396 @@
<!DOCTYPE html>
<html lang="en" xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta name="viewport" content="width=device-width, initial-scale=1">
<meta charset="UTF-8">
<title>Configure CC1101</title>
<link rel="stylesheet" href="main.css" type="text/css" />
<link rel="stylesheet" href="icons.css" type="text/css" />
<style type="text/css">
body {
margin-top: 0px;
}
input[data-type="int8_t"],
input[data-type="uint8_t"] {
width: 47px;
text-align: right;
}
input[data-type="uint16_t"] {
width: 77px;
text-align: right;
}
input[data-type="float"] {
width: 77px;
text-align: right;
}
</style>
<script type="text/javascript">
let baseUrl = ''; //'http://192.168.1.204'; This is the current server.
Number.prototype.round = function (dec) { return Number(Math.round(this + 'e' + dec) + 'e-' + dec); };
Number.prototype.fmt = function (format, empty) {
if (isNaN(this)) return empty || '';
if (typeof format === 'undefined') return this.toString();
let isNegative = this < 0;
let tok = ['#', '0'];
let pfx = '', sfx = '', fmt = format.replace(/[^#\.0\,]/g, '');
let dec = fmt.lastIndexOf('.') > 0 ? fmt.length - (fmt.lastIndexOf('.') + 1) : 0,
fw = '', fd = '', vw = '', vd = '', rw = '', rd = '';
let val = String(Math.abs(this).round(dec));
let ret = '', commaChar = ',', decChar = '.';
for (var i = 0; i < format.length; i++) {
let c = format.charAt(i);
if (c === '#' || c === '0' || c === '.' || c === ',')
break;
pfx += c;
}
for (let i = format.length - 1; i >= 0; i--) {
let c = format.charAt(i);
if (c === '#' || c === '0' || c === '.' || c === ',')
break;
sfx = c + sfx;
}
if (dec > 0) {
let dp = val.lastIndexOf('.');
if (dp === -1) {
val += '.'; dp = 0;
}
else
dp = val.length - (dp + 1);
while (dp < dec) {
val += '0';
dp++;
}
fw = fmt.substring(0, fmt.lastIndexOf('.'));
fd = fmt.substring(fmt.lastIndexOf('.') + 1);
vw = val.substring(0, val.lastIndexOf('.'));
vd = val.substring(val.lastIndexOf('.') + 1);
let ds = val.substring(val.lastIndexOf('.'), val.length);
for (let i = 0; i < fd.length; i++) {
if (fd.charAt(i) === '#' && vd.charAt(i) !== '0') {
rd += vd.charAt(i);
continue;
} else if (fd.charAt(i) === '#' && vd.charAt(i) === '0') {
var np = vd.substring(i);
if (np.match('[1-9]')) {
rd += vd.charAt(i);
continue;
}
else
break;
}
else if (fd.charAt(i) === '0' || fd.charAt(i) === '#')
rd += vd.charAt(i);
}
if (rd.length > 0) rd = decChar + rd;
}
else {
fw = fmt;
vw = val;
}
var cg = fw.lastIndexOf(',') >= 0 ? fw.length - fw.lastIndexOf(',') - 1 : 0;
var nw = Math.abs(Math.floor(this.round(dec)));
if (!(nw === 0 && fw.substr(fw.length - 1) === '#') || fw.substr(fw.length - 1) === '0') {
var gc = 0;
for (let i = vw.length - 1; i >= 0; i--) {
rw = vw.charAt(i) + rw;
gc++;
if (gc === cg && i !== 0) {
rw = commaChar + rw;
gc = 0;
}
}
if (fw.length > rw.length) {
var pstart = fw.indexOf('0');
if (pstart > 0) {
var plen = fw.length - pstart;
var pos = fw.length - rw.length - 1;
while (rw.length < plen) {
let pc = fw.charAt(pos);
if (pc === ',') pc = commaChar;
rw = pc + rw;
pos--;
}
}
}
}
if (isNegative) rw = '-' + rw;
if (rd.length === 0 && rw.length === 0) return '';
//console.log(pfx + rw + rd + sfx);
return pfx + rw + rd + sfx;
};
let fields = [
{ t: 'bool', i: 'printBuffer', d: 'Print the bytes received to the serial console', def: false },
{ t: 'bool', i: 'internalCCMode', d: 'Use internal transmission mode FIFO buffers.', def:true },
{ t: 'uint8_t', i: 'modulationMode', d: 'Modulation mode', o: [{ v: 0, n: '2-FSK' }, { v: 1, n: 'GFSK' }, { v: 2, n: 'ASK/OOK' }, { v: 3, n: '4-FSK' }, { v: 4, n: 'MSK' }] },
{ t: 'float', i: 'frequency', d: 'Basic frequency', def:433.24 },
{ t: 'float', i: 'deviation', d: 'Set the Frequency deviation in kHz. Value from 1.58 to 380.85. Default is 47.60 kHz.', def:47.6 },
{ t: 'uint8_t', i: 'channel', d: 'The channel number from 0 to 255', def:0 },
{ t: 'float', i: 'channelSpacing', d: 'Channel spacing in multiplied by the channel number and added to the base frequency in kHz. 25.39 to 405.45. Default 199.95', def:199.95 },
{ t: 'float', i: 'rxBandwidth', d: 'Receive bandwidth in kHz. Value from 58.03 to 812.50. Default is 812.50kHz', def:812.5 },
{ t: 'float', i: 'dataRate', d: 'The data rate in kBaud. 0.02 to 1621.83 Default is 99.97.', def:99.97 },
{ t: 'int8_t', i: 'txPower', d: 'Transmission power {-30, -20, -15, -10, -6, 0, 5, 7, 10, 11, 12}. Default is 12.', def:12 },
{
t: 'uint8_t', i: 'syncMode', d: 'Sync Mode', def:0, o: [
{ v: 0, n: 'No preamble/sync' },
{ v: 1, n: '16 sync word bits detected' },
{ v: 2, n: '16/16 sync words bits detected.' },
{ v: 3, n: '30/32 sync word bits detected,' },
{ v: 4, n: 'No preamble/sync carrier above threshold' },
{ v: 5, n: '15/16 + carrier above threshold.' },
{ v: 6, n: '16/16 + carrier-sense above threshold' },
{ v: 7, n: '0/32 + carrier-sense above threshold' }]
},
{ t: 'uint16_t', i: 'syncWordHigh', d: 'The High sync word used for the sync mode.', def:211 },
{ t: 'uint16_t', i: 'syncWordLow', d: 'The Low sync word used for the sync mode.', def:145 },
{
t: 'uint8_t', i: 'addrCheckMode', d: 'Address filter check mode', def:0, o: [
{ v: 0, n: 'No address filtration' },
{ v: 1, n: 'Check address without broadcast.' },
{ v: 2, n: 'Address check with 0 as broadcast.' },
{ v: 3, n: 'Address check with 0 or 255 as broadcast.' }]
},
{ t: 'uint8_t', i: 'checkAddr', d: 'Packet filter address depending on addrCheck settings.', def:0 },
{ t: 'bool', i: 'dataWhitening', d: 'Indicates whether data whitening should be applied.', def:false },
{
t: 'uint8_t', i: 'pktFormat', d: 'Packet formatting', def:0, o: [
{ v: 0, n: 'Use FIFO buffers for RX and TX' },
{ v: 1, n: 'Synchronous serial mode. RX on GDO0 and TX on either GDOx pins.' },
{ v: 2, n: 'Random TX mode. Send data using PN9 generator.' },
{ v: 3, n: 'Asynchronous serial mode. RX on GDO0 and TX on either GDOx pins.' }]
},
{
t: 'uint8_t', i: 'pktLengthMode', d: 'Type of packets', def:1, o: [
{ v: 0, n: 'Fixed packet length' },
{ v: 1, n: 'Variable packet length' },
{ v: 2, n: 'Infinite packet length' },
{ v: 3, n: 'Reserved' }]
},
{ t: 'uint8_t', i: 'pktLength', d: 'Packet length', def:0 },
{ t: 'bool', i: 'useCRC', d: 'Indicates whether CRC is to be used.', def:true },
{ t: 'bool', i: 'autoFlushCRC', d: 'Automatically flush RX FIFO when CRC fails. If more than one packet is in the buffer it too will be flushed.', def:false },
{ t: 'bool', i: 'disableDCFilter', d: 'Digital blocking filter for demodulator. Only for data rates <= 250k.', def:false },
{ t: 'bool', i: 'enableManchester', d: 'Enable/disable Manchester encoding.', def:false },
{ t: 'bool', i: 'enableFEC', d: 'Enable/disable forward error correction.', def:false },
{
t: 'uint8_t', i: 'minPreambleBytes', d: 'The minimum number of preamble bytes to be transmitted.', def:0, o: [
{ v: 0, n: '2bytes' },
{ v: 1, n: '3bytes' },
{ v: 2, n: '4bytes' },
{ v: 3, n: '6bytes' },
{ v: 4, n: '8bytes' },
{ v: 5, n: '12bytes' },
{ v: 6, n: '16bytes' },
{ v: 7, n: '24bytes' }]
},
{ t: 'uint8_t', i: 'pqtThreshold', d: 'Preamble quality estimator threshold.', def:0 },
{ t: 'bool', i: 'appendStatus', d: 'Appends the RSSI and LQI values to the TX packed as well as the CRC.', def: false }
];
function resetDefaults() {
for (let i = 0; i < fields.length; i++) {
let f = fields[i];
if (typeof f.def === 'undefined') continue;
let el = document.getElementById(`id_${f.i}`);
switch (f.t) {
case 'bool':
el.checked = f.def;
break;
default:
el.value = f.def;
break;
}
}
}
function loadConfig() {
let overlay = waitMessage(document.getElementById('divFields'));
getJSON('/getRadio', (err, radio) => {
overlay.remove();
if (err) {
console.log(err);
serviceError(document.getElementById('divFields'), err);
}
else {
console.log(radio);
let cfg = radio.config;
// Bind up all the fields.
let elems = document.querySelectorAll('[data-bind]');
for (let i = 0; i < elems.length; i++) {
let el = elems[i];
switch (el.dataset.type) {
case 'bool':
el.checked = cfg[el.dataset.bind];
break;
case 'float':
el.value = cfg[el.dataset.bind].fmt("#.##");
break;
default:
el.value = cfg[el.dataset.bind];
break;
}
}
}
});
}
function createCheckbox(f) { return `<input type="checkbox" id="id_${f.i}" name="${f.i}" data-type="${f.t}" data-bind="${f.bind || f.i}"></input><label for="${f.i}>${f.l || f.i}</label>`; }
function createNumberField(f) { return `<input type="number" id="id_${f.i}" name="${f.i}" data-type="${f.t}" data-bind="${f.bind || f.i}"></input > <label for="${f.i}>${f.l || f.i}</label>`; }
function createDropdown(f) {
let dd = `<select id="id_${f.i}" name="${f.i}" data-type="${f.t}"" data-bind="${f.bind || f.i}">`;
for (let i = 0; i < f.o.length; i++) {
let o = f.o[i];
dd += `<option value="${o.v}">${o.n}</option>`
}
dd += '</select>';
dd += `<label for="${f.i}>${f.l || f.i}</label>`;
return dd;
}
function createFields() {
let shtml = '<div id="divAttrs">';
for (let i = 0; i < fields.length; i++) {
let f = fields[i];
shtml += '<div class="cfg-attr"><div class="cfg-attr-field">'
switch (f.t) {
case 'bool':
shtml += createCheckbox(f);
break;
case 'uint8_t':
case 'int8_t':
case 'uint16_t':
case 'float':
case 'int8_t':
shtml += typeof f.o === 'undefined' ? createNumberField(f) : createDropdown(f);
break;
}
shtml += `</div><div class="cfg-attr-desc">${f.d}</div>`
shtml += '</div>';
}
shtml += '</div>';
document.getElementById('divFields').innerHTML = shtml;
}
function serviceError(el, err) {
let msg = '';
if (typeof err === 'string' && err.startsWith('{')) {
let e = JSON.parse(err);
if (typeof e !== 'undefined' && typeof e.desc === 'string') msg = e.desc;
else msg = err;
}
else if (typeof err === 'string') {
msg = err;
}
else if (typeof err === 'number') {
switch (err) {
case 404:
msg = `404: Service not found`;
break;
default:
msg = `${err}: Network HTTP Error`;
break;
}
}
else if (typeof err !== 'undefined') {
console.log(err);
if (typeof err.desc === 'string') msg = typeof err.desc !== 'undefined' ? err.desc : err.message;
}
return errorMessage(el, msg);
}
function errorMessage(el, msg) {
let div = document.createElement('div');
div.innerHTML = '<div class="innerError">' + msg + '</div><button type="button" onclick="clearErrors();">Close</button></div>';
div.classList.add('errorMessage');
el.appendChild(div);
return div;
}
function getJSON(url, cb) {
let xhr = new XMLHttpRequest();
xhr.open('GET', baseUrl + url, true);
xhr.responseType = 'json';
xhr.onload = () => {
let status = xhr.status;
cb(status === 200 ? null : status, xhr.response);
}
xhr.onerror = (evt) => {
cb(xhr.status || 500, xhr.statusText);
}
xhr.send();
}
function putJSON(url, data, cb) {
let xhr = new XMLHttpRequest();
console.log({ put: baseUrl + url, data: data });
xhr.open('PUT', baseUrl + url, true);
xhr.responseType = 'json';
xhr.setRequestHeader('Content-Type', 'application/json; charset=utf-8');
xhr.setRequestHeader('Accept', 'application/json');
xhr.onload = () => {
let status = xhr.status;
cb(status === 200 ? null : status, xhr.response);
}
xhr.onerror = (evt) => {
cb(xhr.status || 500, xhr.statusText);
}
xhr.send(JSON.stringify(data));
}
function waitMessage(el) {
let div = document.createElement('div');
div.innerHTML = '<div class="lds-roller"><div></div><div></div><div></div><div></div><div></div><div></div><div></div><div></div></div></div>';
div.classList.add('waitoverlay');
el.appendChild(div);
return div;
}
function clearErrors() {
let errors = document.querySelectorAll('div.errorMessage');
if (errors && errors.length > 0) errors.forEach((el) => { el.remove(); });
}
function saveSettings() {
let elems = document.querySelectorAll('[data-bind]');
let obj = {};
for (let i = 0; i < elems.length; i++) {
let el = elems[i];
switch (el.dataset.type) {
case 'bool':
obj[el.dataset.bind] = el.checked;
break;
case 'float':
obj[el.dataset.bind] = parseFloat(el.value);
break;
default:
obj[el.dataset.bind] = parseInt(el.value, 10);
break;
}
}
let overlay = waitMessage(document.getElementById('divFields'));
putJSON('/setRadioConfig', { config: obj }, (err, radio) => {
overlay.remove();
if (err) {
console.log(err);
serviceError(document.getElementById('divFields'), err);
}
else {
console.log(radio);
}
});
}
</script>
</head>
<body>
<div id="divFields"></div>
<div class="button-container">
<button id="btnSaveSetting" type="button" style="display:inline-block;width:44%" onclick="resetDefaults();">
Reset Defaults
</button>
<button id="btnSaveSetting" type="button" style="display:inline-block;width:44%" onclick="saveSettings();">
Save Radio Settings
</button>
</div>
<script type="text/javascript">
createFields();
loadConfig();
</script>
</body>
</html>

620
data/icons.css Normal file
View file

@ -0,0 +1,620 @@
i[class*="icss-"] {
position: relative;
display: inline-block;
font-style: normal;
background-color: currentColor;
box-sizing: border-box;
vertical-align: middle;
}
i[class*="icss-"]:before,
i[class*="icss-"]:after {
content: "";
border-width: 0;
position: absolute;
box-sizing: border-box;
}
/* Size */
[class*="icss-"].xxsmall {
font-size: .45em;
}
[class*="icss-"].xsmall {
font-size: .5em;
}
[class*="icss-"].small {
font-size: .65em;
}
[class*="icss-"].x1_5 {
font-size: 1.5em;
}
[class*="icss-"].x2 {
font-size: 2em;
}
[class*="icss-"].x2_5 {
font-size: 2.5em;
}
[class*="icss-"].x3 {
font-size: 3em;
}
[class*="icss-"].x4 {
font-size: 4em;
}
[class*="icss-"].x5 {
font-size: 5em;
}
/* Align text-bottom */
i[class*="icss-"].bottom {
vertical-align: text-bottom;
}
/* flip */
.flip {
transform: scaleX(-1);
}
/* rotate */
i[class*="icss-"].rot10 {
transform: rotate(10deg);
}
i[class*="icss-"].rot-10 {
transform: rotate(-10deg);
}
i[class*="icss-"].rot20 {
transform: rotate(20deg);
}
i[class*="icss-"].rot-20 {
transform: rotate(-20deg);
}
i[class*="icss-"].rot45 {
transform: rotate(45deg);
}
i[class*="icss-"].rot-45 {
transform: rotate(-45deg);
}
i[class*="icss-"].rot90 {
transform: rotate(90deg);
}
i[class*="icss-"].rot-90 {
transform: rotate(-90deg);
}
i[class*="icss-"].rot180 {
transform: rotate(180deg);
}
i[class*="icss-"].rot-180 {
transform: rotate(-180deg);
}
/* force animation */
i.icss-anim,
i.icss-anim:before,
i.icss-anim:after {
transition: all 1s;
}
/* Spin */
.icss-spin {
animation: spin 2s infinite linear;
}
.icss-pulse {
animation: spin 1s infinite steps(8);
}
.icss-spin-hover:hover {
animation: spin 2s infinite linear;
}
@keyframes spin {
0% {
transform: rotate(0deg);
}
100% {
transform: rotate(359deg);
}
}
/* BELL */
@keyframes ring {
0% {
transform: rotate(-15deg)
}
2% {
transform: rotate(15deg)
}
4% {
transform: rotate(-18deg)
}
6% {
transform: rotate(18deg)
}
8% {
transform: rotate(-22deg)
}
10% {
transform: rotate(22deg)
}
12% {
transform: rotate(-18deg)
}
14% {
transform: rotate(18deg)
}
16% {
transform: rotate(-12deg)
}
18% {
transform: rotate(12deg)
}
20%,100% {
transform: rotate(0deg)
}
}
.icss-ring {
animation: ring 2s infinite ease;
}
.icss-ring-hover:hover {
animation: ring 2s infinite ease;
}
/* VERTICAL */
@keyframes vertical {
0% {
transform: translate(0,-3px)
}
4% {
transform: translate(0,3px)
}
8% {
transform: translate(0,-3px)
}
12% {
transform: translate(0,3px)
}
16% {
transform: translate(0,-3px)
}
20% {
transform: translate(0,3px)
}
22%,100% {
transform: translate(0,0)
}
}
.icss-vibes,
.icss-vibes-hover:hover {
animation: vertical 2s ease infinite;
}
/* HORIZONTAL */
@keyframes horizontal {
0% {
transform: translate(0,0)
}
6% {
transform: translate(5px,0)
}
12% {
transform: translate(0,0)
}
18% {
transform: translate(5px,0)
}
24% {
transform: translate(0,0)
}
30% {
transform: translate(5px,0)
}
36%,100% {
transform: translate(0,0)
}
}
.icss-shake,
.icss-shake-hover:hover {
animation: horizontal 2s ease infinite;
}
/* TADA */
@keyframes tada {
0% {
transform: scale(1)
}
10%,20% {
transform: scale(.9) rotate(-8deg);
}
30%,50%,70% {
transform: scale(1.3) rotate(8deg)
}
40%,60% {
transform: scale(1.3) rotate(-8deg)
}
80%,100% {
transform: scale(1) rotate(0)
}
}
.icss-tada,
.icss-tada-hover:hover {
animation: tada 2s linear infinite;
}
/* Reverse animation */
.icss-reverse {
animation-direction: reverse;
}
[class*="-hover"].icss-reverse:hover {
animation-direction: reverse;
}
/* Stack icons */
.icss-stack {
position: relative;
width: 1em;
height: 1em;
display: inline-block;
}
.icss-stack i[class*="icss-"] {
position: absolute;
top: 50%;
left: 50%;
transform: translate(-.5em, -.5em);
}
.icss-stack i[class*="icss-"].bottom {
bottom: 0;
top: auto;
}
/* shadow icon */
.icss-shadow {
position: relative;
width: 1em;
height: 1em;
display: inline-block;
}
.icss-shadow i[class*="icss-"] {
position: absolute;
top: 50%;
left: 50%;
transform: translate(-.5em, -.5em);
}
.icss-shadow i[class*="icss-"]:first-child {
top: 54%;
left: 54%;
}
i.icss-edit {
width: 1em;
height: 1em;
background-color: transparent;
border-radius: 50% 45% 50% 35%;
overflow: hidden;
margin: 0;
}
i.icss-edit:before {
width: .3em;
height: .8em;
border: .15em solid transparent;
border-top: .24em solid currentColor;
transform: rotate(45deg) translate(-50%);
transform-origin: 0 0;
box-shadow: 0 -.05em, .24em -.8em, -.24em -.8em, 0 -1.5em;
clip: rect(-.9em .3em 1em 0);
left: .25em;
top: .75em;
}
i.icss-edit:after {
width: .1em;
height: 0;
background-color: transparent;
transform: translate(-50%, -50%);
top: 50%;
left: 50%;
}
i.icss-trash {
width: .68em;
height: .9em;
background-color: transparent;
border-width: .1em .1em;
border-style: solid;
border-radius: .05em;
margin: .1em .15em 0;
}
i.icss-trash:before {
border-style: solid;
border-width: .1em;
top: -.23em;
left: 50%;
border-radius: .1em;
width: .275em;
height: 1.03em;
transform: translateX(-50%);
}
i.icss-trash:after {
border-width: .1em .43em;
border-style: solid;
left: 50%;
top: -.05em;
border-radius: .07em;
transform: translateX(-50%);
}
i.icss-gear {
width: .5em;
height: .5em;
position: relative;
border-radius: 100%;
background-color: transparent;
border-width: .07em;
border-style: solid;
border-color: transparent;
margin: .25em;
box-shadow: 0 0 0 .1em, inset 0 0 0 .3em;
}
i.icss-gear:before {
width: .18em;
height: .18em;
top: 50%;
left: 50%;
transform: translate(-50%, -50%);
box-shadow: .41em 0, -.41em 0, 0 .41em, 0 -.41em;
}
i.icss-gear:after {
width: .18em;
height: .18em;
top: 50%;
left: 50%;
transform: translate(-50%, -50%) rotate(45deg);
box-shadow: .42em 0, -.42em 0, 0 .42em, 0 -.42em;
}
i.icss-gears {
width: .5em;
height: .5em;
position: relative;
border-radius: 100%;
border-width: .063em;
border-style: solid;
border-color: transparent;
margin: .36em .532em .08em .1em;
box-shadow: .51em -.32em 0 -.06em;
}
i.icss-gears:before {
width: .7em;
height: .7em;
border-radius: 100%;
background: linear-gradient(0deg,transparent 39%,currentcolor 39%,currentcolor 61%, transparent 61%), linear-gradient(60deg,transparent 42%, currentcolor 42%,currentcolor 58%, transparent 58%), linear-gradient(120deg,transparent 42%, currentcolor 42%,currentcolor 58%, transparent 58%);
top: 50%;
left: 50%;
transform: translate(-50%, -50%);
}
i.icss-gears:after {
width: .55em;
height: .55em;
border-radius: 100%;
background: linear-gradient(0deg,transparent 37%,currentcolor 37%,currentcolor 63%, transparent 63%), linear-gradient(60deg,transparent 40%, currentcolor 40%,currentcolor 60%, transparent 60%), linear-gradient(120deg,transparent 40%, currentcolor 40%,currentcolor 60%, transparent 60%);
top: -.135em;
left: .695em;
transform: translate(-50%, -50%) rotate(25deg);
}
i.icss-somfy-down {
width: 1em;
height: 1em;
border-radius: .07em;
background-color: transparent;
margin: 0;
}
i.icss-somfy-down:before {
height: .6em;
width: .6em;
border: .15em solid currentColor;
border-color: currentColor currentColor transparent transparent;
top: 50%;
left: 50%;
transform: translate(-50%,-70%) rotate(135deg);
}
i.icss-somfy-up {
width: 1em;
height: 1em;
border-radius: .07em;
background-color: transparent;
margin: 0;
}
i.icss-somfy-up:before {
height: .6em;
width: .6em;
border: .15em solid currentColor;
border-color: currentColor currentColor transparent transparent;
top: 50%;
left: 50%;
transform: translate(-50%,-30%) rotate(-45deg);
}
i.icss-home {
width: .8em;
height: .45em;
background-color: transparent;
border-width: 0;
border-style: solid;
border-radius: 0 0 .02em .02em;
box-shadow: inset .285em .1em, inset -.285em .1em;
margin: .55em .1em 0;
}
i.icss-home:before {
border-width: 0 .4em .4em;
border-style: solid;
border-color: currentColor transparent;
transform: translateX(-50%);
box-shadow: 0 .1em;
top: -.4em;
left: 50%;
}
i.icss-home:after {
width: .76em;
height: .76em;
border-width: 0.065em 0 0 0.065em;
border-style: solid;
transform: translateX(-50%) rotate(45deg);
top: -0.4em;
left: 50%;
}
i.icss-window {
width: 1.1em;
height: .75em;
background-color: transparent;
border: .05em solid transparent;
border-width: 0 .1em;
box-shadow: inset 0 0 0 .07em, inset 0 .19em 0 .07em, 0 .07em 0;
margin: .2em 0 .07em;
}
i.icss-window:before {
width: 1.1em;
height: .26em;
border-bottom: .1em solid transparent;
box-shadow: inset 0 1em, 0 .48em 0 -.1em;
top: -.2em;
left: -.1em;
}
i.icss-window:after {
width: 0.06em;
height: .7em;
background-color: currentColor;
left: .43em;
}
i.icss-window-shade {
width: 1.1em;
height: .75em;
background-color: transparent;
border: .05em solid transparent;
border-width: 0 .1em;
box-shadow: inset 0 0 0 .01em, inset 0 .01em 0 .07em, 0 .07em 0;
margin: .2em 0 .07em;
}
i.icss-window-shade:before {
width: 1.1em;
height: .2em;
border-bottom: .1em solid transparent;
box-shadow: inset 0 1em, 0 0em 0 -.1em;
top: -.15em;
left: -.1em;
}
i.icss-window-shade:after {
width: calc(100% - .05em);
height: var(--shade-position, 0%);
left: 0.025em;
top: 0.025em;
border-bottom: solid 0.025em gray;
background-image: repeating-conic-gradient(var(--shade-color, currentColor) 0% 25%, rgba(71, 212, 255, 0) 0% 50%);
background-position: 0 0, 100% 100%;
background-size: 0.05em 0.05em;
background-color: rgba(71, 212, 255, 0);
}
i.icss-upload {
width: 1em;
height: .6em;
background-color: transparent;
border-width: 0 .2em .3em;
border-style: solid;
border-radius: .03em;
margin: .4em 0 0;
}
i.icss-upload:before {
height: .5em;
border-style: solid;
border-width: 0 .25em .25em;
border-color: transparent;
border-bottom-color: currentColor;
background-color: transparent;
box-shadow: 0em .35em 0 -.13em;
top: -.6em;
left: 50%;
transform: translateX(-50%);
}
i.icss-upload:after {
}
i.icss-file {
width: .8em;
height: 1em;
background-color: transparent;
border-width: .065em;
border-style: solid;
border-radius: .05em .34em .05em .05em;
}
i.icss-file:before {
border-style: solid;
border-width: .2em;
left: .275em;
border-radius: .1em;
border-color: transparent;
border-right-color: currentColor;
transform: rotate(-45deg);
top: .02em;
}

1361
data/index.html Normal file

File diff suppressed because it is too large Load diff

514
data/main.css Normal file
View file

@ -0,0 +1,514 @@
:root {
--shade-color: #00bcd4;
}
* {
box-sizing: border-box;
}
input[type="range"] {
accent-color: #00bcd4;
outline:none;
}
input[type="range"]:active {
outline: dotted 1px silver;
}
body {
color: #434343;
font-family: "Helvetica Neue",Helvetica,Arial,sans-serif;
font-size: 14px;
background-color: #eeeeee;
margin-top: 77px;
box-sizing: border-box;
}
.container {
margin: 0 auto;
max-width: 450px;
padding: 20px;
box-shadow: 0 10px 20px rgba(0,0,0,0.19), 0 6px 6px rgba(0,0,0,0.23);
background-color: #ffffff;
}
h1 {
text-align: center;
margin-bottom: 10px;
margin-top: 0px;
color: #939393;
font-size: 28px;
}
form {
margin-top:-18px;
}
form .field-group {
box-sizing: border-box;
clear: both;
padding: 4px 0;
position: relative;
margin: 1px 0;
width: 100%;
}
form .field-group1 {
box-sizing: border-box;
clear: both;
padding: 4px 0;
position: relative;
margin: 1px 0;
width: 100%;
}
form .field-group1 > span {
color: #757575;
display: inline-block;
margin: 0 0 5px 0;
padding: 5px 0 0;
position: relative;
word-wrap: break-word;
font-size: 15px;
font-weight: bold;
}
form .field-group > label {
display: block;
margin: 0px;
padding: 3px 0 0;
position: relative;
word-wrap: break-word;
line-height:4px;
font-size:14px;
margin-bottom:10px;
margin-top:-10px;
color:#00bcd4;
}
form .field-group1 > div.field-group {
display:inline-block;
width:auto;
}
::placeholder {
opacity: .5;
}
input[type=password],
input[type=number],
input[type=text] {
font-size: 15px;
margin-bottom: 14px;
-webkit-appearance: none;
background: #fafafa;
color: #636363;
border: none;
border-radius: 0;
border-top: none;
border-left: none;
border-right: none;
border-bottom: 1px solid #00bcd4;
background-color: transparent;
}
select {
font-size: 15px;
-webkit-appearance: none;
background: #fafafa;
color: #636363;
border: none;
border-radius: 0;
border-top: none;
border-left: none;
border-right: none;
border-bottom: 1px solid #00bcd4;
background-color: transparent;
margin-bottom:14px;
}
form .field-group input[type=password],
form .field-group input[type=number],
form .field-group input[type=text] {
display: block;
width: 100%;
}
select:focus,
input[type=password]:focus,
input[type=number]:focus,
input[type=text]:focus {
border-color: #4C669F;
outline: 0;
}
.button-container {
box-sizing: border-box;
clear: both;
margin: 1px 0 0;
padding: 4px 0;
position: relative;
width: 100%;
}
button[type=button],
button[type=submit] {
background: #00bcd4;
border: none;
border-radius: 30px;
color: #ffffff;
cursor: pointer;
display: block;
font-weight: bold;
font-size: 14px;
padding: 10px 0;
margin-top: 10px;
text-align: center;
text-transform: uppercase;
width: 100%;
-webkit-transition: background 250ms ease;
-moz-transition: background 250ms ease;
-o-transition: background 250ms ease;
transition: background 250ms ease;
}
button:active {
opacity: .7;
}
a {
text-decoration: none;
color: #00bcd4;
position: fixed;
right: 12px;
font-size: 18px;
bottom: 7px;
border-bottom: 1px solid #00bcd4;
}
div.errorMessage {
position:absolute;
left:0px;
top:0px;
width:100%;
height:100%;
color:white;
display:flex;
flex-wrap:wrap;
background:gray;
opacity:.9;
padding:10px;
align-items:center;
align-content:center;
font-size:32px;
border-radius:5px;
}
div.errorMessage > div {
padding:10px;
}
div.instructions {
position: absolute;
left: 0px;
top: 0px;
width: 100%;
height: 100%;
color: white;
display: flex;
flex-wrap: wrap;
background: gray;
opacity: .9;
padding: 10px;
align-items: center;
align-content: center;
font-size: 20px;
border-radius: 5px;
}
div.instructions > div {
padding: 10px;
}
.tab-container {
font-size:20px;
text-align:center;
}
.tab-container > span {
margin-left: 5px;
margin-right: 5px;
padding-bottom: 3px;
display: inline-block;
border-bottom: 1px solid #00bcd4;
color: #00bcd4;
cursor:pointer;
}
.tab-container > span.selected {
border-bottom-width: 3px;
font-weight: bold;
}
fieldset {
display: block;
border: 1px solid #ccc;
border-radius: 5px;
padding: 25px;
margin-top: 20px;
position: relative;
}
input[type=checkbox] {
width:20px;
height:20px;
vertical-align:middle;
}
div.field-group1.inputPin {
margin-top:-10px;
}
legend {
border: 1px solid #ccc;
border-bottom: 0;
border-radius: 5px 5px 0 0;
padding: 8px 18px 0;
position: relative;
top: -14px;
}
div.wifiSignal {
white-space: nowrap;
height: 37px;
cursor: pointer;
padding-left: 10px;
padding-right: 10px;
}
div.wifiSignal:hover {
background: #00bcd4;
color: white;
}
div.wifiSignal > span {
display: inline-block;
vertical-align: middle;
}
span.ssid {
width: calc(100% - 50px);
margin-top: 10px;
}
#divAps {
max-height: 200px;
overflow-y: auto;
overflow-x: hidden;
height: 150px;
padding-right: 7px;
}
div.signal {
margin: 0px;
color: lawngreen;
height: 32px;
width: 32px;
float: right;
}
span.strength {
position: relative;
margin-top: 2px;
}
.wave {
display: inline-block;
border: 4px solid transparent;
border-top-color: currentColor;
border-radius: 50%;
border-style: solid;
margin: 2px;
}
.waveStrength-4 .wv4.wave,
.waveStrength-3 .wv4.wave,
.waveStrength-3 .wv3.wave,
.waveStrength-2 .wv4.wave,
.waveStrength-2 .wv3.wave,
.waveStrength-2 .wv2.wave,
.waveStrength-1 .wv4.wave,
.waveStrength-1 .wv3.wave,
.waveStrength-1 .wv2.wave,
.waveStrength-1 .wv1.wave,
.waveStrength-0 .wv4.wave,
.waveStrength-0 .wv3.wave,
.waveStrength-0 .wv2.wave,
.waveStrength-0 .wv1.wave,
.waveStrength-0 .wv0.wave {
border-top-color: #eee;
}
button.disabled {
opacity:.3;
}
div.waitoverlay {
width: 100%;
height: 100%;
position: absolute;
display: flex;
justify-content: center;
align-items: center;
top:0px;
left:0px;
background:rgba(227, 226, 230, 0.46);
cursor:no-drop;
z-index:20000;
}
div.waitoverlay > .lds-roller {
z-index:1000;
opacity:1;
}
.lds-roller {
display: inline-block;
position: relative;
width: 80px;
height: 80px;
}
.lds-roller div {
animation: lds-roller 1.2s cubic-bezier(0.5, 0, 0.5, 1) infinite;
transform-origin: 40px 40px;
}
.lds-roller div:after {
content: " ";
display: block;
position: absolute;
width: 7px;
height: 7px;
border-radius: 50%;
background: gray;
margin: -4px 0 0 -4px;
}
.lds-roller div:nth-child(1) {
animation-delay: -0.036s;
}
.lds-roller div:nth-child(1):after {
top: 63px;
left: 63px;
}
.lds-roller div:nth-child(2) {
animation-delay: -0.072s;
}
.lds-roller div:nth-child(2):after {
top: 68px;
left: 56px;
}
.lds-roller div:nth-child(3) {
animation-delay: -0.108s;
}
.lds-roller div:nth-child(3):after {
top: 71px;
left: 48px;
}
.lds-roller div:nth-child(4) {
animation-delay: -0.144s;
}
.lds-roller div:nth-child(4):after {
top: 72px;
left: 40px;
}
.lds-roller div:nth-child(5) {
animation-delay: -0.18s;
}
.lds-roller div:nth-child(5):after {
top: 71px;
left: 32px;
}
.lds-roller div:nth-child(6) {
animation-delay: -0.216s;
}
.lds-roller div:nth-child(6):after {
top: 68px;
left: 24px;
}
.lds-roller div:nth-child(7) {
animation-delay: -0.252s;
}
.lds-roller div:nth-child(7):after {
top: 63px;
left: 17px;
}
.lds-roller div:nth-child(8) {
animation-delay: -0.288s;
}
.lds-roller div:nth-child(8):after {
top: 56px;
left: 12px;
}
@keyframes lds-roller {
0% {
transform: rotate(0deg);
}
100% {
transform: rotate(360deg);
}
}
.radioPins > select {
width: 70px;
text-align:center;
}
.radioPins > label {
text-align:center;
}
.somfyShade {
text-align:center;
}
.button-outline {
background-color: #00bcd4;
border-radius:50%;
padding:3px 5px 5px 5px;
margin-left:2px;
margin-right:2px;
display:inline-block;
font-size:1.5em;
color:white;
}
.shade-name {
text-align:left;
width: 124px;
padding-left: 2px;
padding-right: 2px;
display: inline-block;
text-overflow: ellipsis;
overflow:hidden;
}
.shade-address {
width:77px;
padding-left:2px;
padding-right:2px;
text-overflow:ellipsis;
overflow:hidden;
display:inline-block;
}
.progress-bar {
display:block;
width:100%;
background:white;
border-radius:calc(1em / 2);
height:1em;
overflow:hidden;
position:relative;
}
.progress-bar::after {
content: attr(data-progress);
display: block;
position: absolute;
width: 100%;
background: none;
font-size: .7em;
vertical-align: middle;
margin-top: .15em;
color: darkslategray;
top:0px;
left:0px;
}
.progress-bar::before {
content: "";
width: var(--progress);
text-align: right;
background-color: #00bcd4;
border-radius: .5em;
height: 1em;
display: block;
overflow: hidden;
}

14
debug.cfg Normal file
View file

@ -0,0 +1,14 @@
# SPDX-License-Identifier: GPL-2.0-or-later
#
# Example OpenOCD configuration file for ESP32-WROVER-KIT board.
#
# For example, OpenOCD can be started for ESP32 debugging on
#
# openocd -f board/esp32-wrover-kit-3.3v.cfg
#
# Source the JTAG interface configuration file
source [find interface/ftdi/esp32_devkitj_v1.cfg]
set ESP32_FLASH_VOLTAGE 3.3
# Source the ESP32 configuration file
source [find target/esp32.cfg]

19
debug_custom.json Normal file
View file

@ -0,0 +1,19 @@
{
"name":"Arduino on ESP32",
"toolchainPrefix":"xtensa-esp32-elf",
"svdFile":"esp32.svd",
"request":"attach",
"postAttachCommands":[
"set remote hardware-watchpoint-limit 2",
"monitor reset halt",
"monitor gdb_sync",
"thb setup",
"c"
],
"overrideRestartCommands":[
"monitor reset halt",
"monitor gdb_sync",
"thb setup",
"c"
]
}

46087
esp32.svd Normal file

File diff suppressed because it is too large Load diff