Code cleanup

Enable/Disable radio from the UI to release the receive interrupt.  This helps when trying to use Arduino IDE to update firmware.
This commit is contained in:
Robert Strouse 2023-01-25 15:40:21 -08:00
parent fd6dc68af0
commit 26714f71b7
8 changed files with 196 additions and 124 deletions

View file

@ -211,6 +211,10 @@ bool WifiSettings::load() {
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->hostname[sizeof(this->hostname) - 1] = '\0';
this->ssid[sizeof(this->ssid) - 1] = '\0';
this->passphrase[sizeof(this->passphrase) - 1] = '\0';
if(strlen(this->hostname) == 0) strlcpy(this->hostname, "ESPSomfyRTS", sizeof(this->hostname));
this->ssdpBroadcast = pref.getBool("ssdpBroadcast", true);
pref.end();
return true;

View file

@ -2,7 +2,7 @@
#ifndef configsettings_h
#define configsettings_h
#define FW_VERSION "v1.0.7"
#define FW_VERSION "v1.0.8"
enum DeviceStatus {
DS_OK = 0,
DS_ERROR = 1,

View file

@ -230,7 +230,6 @@ void somfy_frame_t::print() {
Serial.print(" CS:");
Serial.println(this->checksum);
}
void SomfyShadeController::end() { this->transceiver.disableReceive(); }
SomfyShadeController::SomfyShadeController() {
memset(this->m_shadeIds, 255, sizeof(this->m_shadeIds));
@ -299,6 +298,14 @@ SomfyShade * SomfyShadeController::getShadeById(uint8_t shadeId) {
return nullptr;
}
bool SomfyShade::linkRemote(uint32_t address, uint16_t rollingCode) {
// Check to see if the remote is already linked. If it is
// just return true after setting the rolling code
for(uint8_t i = 0; i < SOMFY_MAX_LINKED_REMOTES; i++) {
if(this->linkedRemotes[i].getRemoteAddress() == address) {
this->linkedRemotes[i].setRollingCode(rollingCode);
return true;
}
}
for(uint8_t i = 0; i < SOMFY_MAX_LINKED_REMOTES; i++) {
if(this->linkedRemotes[i].getRemoteAddress() == 0) {
char shadeKey[15];
@ -950,6 +957,7 @@ static struct somfy_rx_t
uint8_t receive_buffer[10]; // 80 bits
bool packet_received = false;
void Transceiver::sendFrame(byte *frame, uint8_t sync) {
if(!this->config.enabled) return;
uint32_t pin = 1 << this->config.TXPin;
if (sync == 2) { // Only with the first frame.
// Wake-up pulse & Silence
@ -1063,7 +1071,9 @@ void RECEIVE_ATTR Transceiver::handleReceive() {
bool Transceiver::receive() {
if (packet_received) {
packet_received = false;
this->frame.rssi = ELECHOUSE_cc1101.getRssi();
this->frame.decodeFrame(receive_buffer);
//this->frame.lqi = ELECHOUSE_cc1101.getLqi();
if (!this->frame.valid) this->clearReceived();
return this->frame.valid;
}
@ -1072,17 +1082,23 @@ bool Transceiver::receive() {
void Transceiver::clearReceived(void) {
packet_received = false;
memset(receive_buffer, 0x00, sizeof(receive_buffer));
if(this->config.enabled)
attachInterrupt(interruptPin, handleReceive, CHANGE);
}
void Transceiver::enableReceive(void) {
if(this->config.enabled) {
Serial.print("Enabling receive on Pin #");
Serial.println(this->config.RXPin);
pinMode(this->config.RXPin, INPUT);
interruptPin = digitalPinToInterrupt(this->config.RXPin);
ELECHOUSE_cc1101.SetRx();
attachInterrupt(interruptPin, handleReceive, CHANGE);
}
}
void Transceiver::disableReceive(void) {
if(interruptPin > 0) detachInterrupt(interruptPin);
interruptPin = 0;
}
void Transceiver::disableReceive(void) { detachInterrupt(interruptPin); }
bool Transceiver::toJSON(JsonObject& obj) {
Serial.println("Setting Transceiver Json");
JsonObject objConfig = obj.createNestedObject("config");
@ -1090,7 +1106,6 @@ bool Transceiver::toJSON(JsonObject& obj) {
return true;
}
bool Transceiver::fromJSON(JsonObject& obj) {
if (obj.containsKey("config")) {
JsonObject objConfig = obj["config"];
this->config.fromJSON(objConfig);
@ -1099,9 +1114,10 @@ bool Transceiver::fromJSON(JsonObject& obj) {
}
bool Transceiver::save() {
this->config.save();
ELECHOUSE_cc1101.setRxBW(this->config.rxBandwidth); // Set the Receive Bandwidth in kHz. Value from 58.03 to 812.50. Default is 812.50 kHz.
ELECHOUSE_cc1101.setPA(this->config.txPower); // Set TxPower. The following settings are possible depending on the frequency band. (-30 -20 -15 -10 -6 0 5 7 10 11 12) Default is max!
ELECHOUSE_cc1101.setDeviation(this->config.deviation);
this->config.apply();
//ELECHOUSE_cc1101.setRxBW(this->config.rxBandwidth); // Set the Receive Bandwidth in kHz. Value from 58.03 to 812.50. Default is 812.50 kHz.
//ELECHOUSE_cc1101.setPA(this->config.txPower); // Set TxPower. The following settings are possible depending on the frequency band. (-30 -20 -15 -10 -6 0 5 7 10 11 12) Default is max!
//ELECHOUSE_cc1101.setDeviation(this->config.deviation);
return true;
}
bool Transceiver::end() {
@ -1139,6 +1155,7 @@ void transceiver_config_t::fromJSON(JsonObject& obj) {
if (obj.containsKey("pqtThreshold")) this->pqtThreshold = obj["pqtThreshold"];
if (obj.containsKey("appendStatus")) this->appendStatus = obj["appendStatus"];
if (obj.containsKey("printBuffer")) this->printBuffer = obj["printBuffer"];
if(obj.containsKey("enabled")) this->enabled = obj["enabled"];
}
void transceiver_config_t::toJSON(JsonObject& obj) {
obj["type"] = this->type;
@ -1175,6 +1192,7 @@ void transceiver_config_t::toJSON(JsonObject& obj) {
obj["pqtThreshold"] = this->pqtThreshold;
obj["appendStatus"] = this->appendStatus;
obj["printBuffer"] = somfy.transceiver.printBuffer;
obj["enabled"] = this->enabled;
Serial.print("Serialize Radio JSON ");
Serial.printf("SCK:%u MISO:%u MOSI:%u CSN:%u RX:%u TX:%u\n", this->SCKPin, this->MISOPin, this->MOSIPin, this->CSNPin, this->RXPin, this->TXPin);
}
@ -1213,6 +1231,7 @@ void transceiver_config_t::save() {
pref.putUChar("minPreambleBytes", this->minPreambleBytes);
pref.putUChar("pqtThreshold", this->pqtThreshold);
pref.putBool("appendStatus", this->appendStatus);
pref.putBool("enabled", this->enabled);
pref.end();
Serial.print("Save Radio Settings ");
Serial.printf("SCK:%u MISO:%u MOSI:%u CSN:%u RX:%u TX:%u\n", this->SCKPin, this->MISOPin, this->MOSIPin, this->CSNPin, this->RXPin, this->TXPin);
@ -1252,28 +1271,37 @@ void transceiver_config_t::load() {
this->minPreambleBytes = pref.getUChar("minPreambleBytes", this->minPreambleBytes);
this->pqtThreshold = pref.getUChar("pqtThreshold", this->pqtThreshold);
this->appendStatus = pref.getBool("appendStatus", this->appendStatus);
this->enabled = pref.getBool("enabled", this->enabled);
pref.end();
this->printBuffer = somfy.transceiver.printBuffer;
}
void transceiver_config_t::apply() {
somfy.transceiver.disableReceive();
bit_length = this->type;
if(this->enabled) {
Serial.print("Applying radio settings ");
Serial.printf("SCK:%u MISO:%u MOSI:%u CSN:%u RX:%u TX:%u\n", this->SCKPin, this->MISOPin, this->MOSIPin, this->CSNPin, this->RXPin, this->TXPin);
ELECHOUSE_cc1101.setGDO(this->RXPin, this->TXPin);
Serial.println("Set GDO");
ELECHOUSE_cc1101.setSpiPin(this->SCKPin, this->MISOPin, this->MOSIPin, this->CSNPin);
Serial.println("Set SPI");
ELECHOUSE_cc1101.Init();
Serial.println("Initialized");
ELECHOUSE_cc1101.setMHZ(this->frequency); // Here you can set your basic frequency. The lib calculates the frequency automatically (default = 433.92).The cc1101 can: 300-348 MHZ, 387-464MHZ and 779-928MHZ. Read More info from datasheet.
Serial.println("Set Frequency");
ELECHOUSE_cc1101.setRxBW(this->rxBandwidth); // Set the Receive Bandwidth in kHz. Value from 58.03 to 812.50. Default is 812.50 kHz.
Serial.println("Set RxBW");
ELECHOUSE_cc1101.setPA(this->txPower); // Set TxPower. The following settings are possible depending on the frequency band. (-30 -20 -15 -10 -6 0 5 7 10 11 12) Default is max!
ELECHOUSE_cc1101.setCCMode(this->internalCCMode); // set config for internal transmission mode.
ELECHOUSE_cc1101.setModulation(this->modulationMode); // set modulation mode. 0 = 2-FSK, 1 = GFSK, 2 = ASK/OOK, 3 = 4-FSK, 4 = MSK.
if (!ELECHOUSE_cc1101.getCC1101()) {
Serial.println("Error setting up the radio");
}
else {
Serial.println("Successfully set up the radio");
somfy.transceiver.enableReceive();
}
}
else {
ELECHOUSE_cc1101.setSidle();
somfy.transceiver.disableReceive();
}
/*
ELECHOUSE_cc1101.setDeviation(this->deviation); // Set the Frequency deviation in kHz. Value from 1.58 to 380.85. Default is 47.60 kHz.
ELECHOUSE_cc1101.setChannel(this->channel); // Set the Channelnumber from 0 to 255. Default is cahnnel 0.
@ -1297,13 +1325,6 @@ void transceiver_config_t::apply() {
ELECHOUSE_cc1101.setAppendStatus(this->appendStatus); // When enabled, two status bytes will be appended to the payload of the packet. The status bytes contain RSSI and LQI values, as well as CRC OK.
*/
//somfy.transceiver.printBuffer = this->printBuffer;
if (!ELECHOUSE_cc1101.getCC1101()) {
Serial.println("Error setting up the radio");
}
else {
Serial.println("Successfully set up the radio");
somfy.transceiver.enableReceive();
}
}
bool Transceiver::begin() {
this->config.load();
@ -1314,19 +1335,23 @@ void Transceiver::loop() {
if (this->receive()) {
this->clearReceived();
somfy.processFrame(this->frame, false);
char buf[128];
sprintf(buf, "{\"encKey\":%d, \"address\":%d, \"rcode\":%d, \"command\":\"%s\"}", this->frame.encKey, this->frame.remoteAddress, this->frame.rollingCode, translateSomfyCommand(this->frame.cmd));
char buf[177];
sprintf(buf, "{\"encKey\":%d, \"address\":%d, \"rcode\":%d, \"command\":\"%s\", \"rssi\":%d}", this->frame.encKey, this->frame.remoteAddress, this->frame.rollingCode, translateSomfyCommand(this->frame.cmd), this->frame.rssi);
sockEmit.sendToClients("remoteFrame", buf);
}
}
somfy_frame_t& Transceiver::lastFrame() { return this->frame; }
void Transceiver::beginTransmit() {
if(this->config.enabled) {
this->disableReceive();
pinMode(this->config.TXPin, OUTPUT);
ELECHOUSE_cc1101.SetTx();
}
}
void Transceiver::endTransmit() {
if(this->config.enabled) {
ELECHOUSE_cc1101.setSidle();
delay(100);
this->enableReceive();
}
}

View file

@ -92,6 +92,7 @@ class SomfyShade : public SomfyRemote {
typedef struct transceiver_config_t {
bool printBuffer = false;
bool enabled = true;
uint8_t type = 56; // 56 or 80 bit protocol.
uint8_t SCKPin = 18;
uint8_t TXPin = 12;

Binary file not shown.

Binary file not shown.

View file

@ -629,7 +629,7 @@ void Web::begin() {
else {
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Remote address not provided.\"}"));
}
DynamicJsonDocument sdoc(256);
DynamicJsonDocument sdoc(512);
JsonObject sobj = sdoc.to<JsonObject>();
shade->toJSON(sobj);
serializeJson(sdoc, g_content);
@ -677,7 +677,7 @@ void Web::begin() {
else {
server.send(500, _encoding_json, F("{\"status\":\"ERROR\",\"desc\":\"Remote address not provided.\"}"));
}
DynamicJsonDocument sdoc(256);
DynamicJsonDocument sdoc(512);
JsonObject sobj = sdoc.to<JsonObject>();
shade->toJSON(sobj);
serializeJson(sdoc, g_content);

View file

@ -1,4 +1,5 @@
<!DOCTYPE html>
<html>
<head>
<meta name="viewport" content="width=device-width, initial-scale=1">
@ -166,7 +167,7 @@
});
};
setAppVersion() { document.getElementById('spanAppVersion').innerText = 'v1.0.7'; };
setAppVersion() { document.getElementById('spanAppVersion').innerText = 'v1.0.8'; };
setTimeZones() {
let dd = document.getElementById('selTimeZone');
dd.length = 0;
@ -215,6 +216,7 @@
};
rebootDevice() {
promptMessage(document.getElementById('fsGeneralSettings'), 'Are you sure you want to reboot the device?', () => {
socket.close(3000, 'reboot');
let overlay = waitMessage(document.getElementById('fsGeneralSettings'));
putJSON('/reboot', {}, (err, response) => {
overlay.remove();
@ -367,11 +369,12 @@
document.getElementById('selTransRXPin').value = somfy.transceiver.config.RXPin.toString();
document.getElementById('selRadioType').value = somfy.transceiver.config.type;
document.getElementById('spanMaxShades').innerText = somfy.maxShades;
document.getElementById('spanRxBandwidth').innerText = Math.round(somfy.transceiver.config.rxBandwidth * 100) / 100;
document.getElementById('spanRxBandwidth').innerText = (Math.round(somfy.transceiver.config.rxBandwidth * 100) / 100).fmt('#,##0.00');
document.getElementById('slidRxBandwidth').value = Math.round(somfy.transceiver.config.rxBandwidth * 100);
document.getElementById('spanTxPower').innerText = somfy.transceiver.config.txPower;
document.getElementById('spanDeviation').innerText = Math.round(somfy.transceiver.config.deviation * 100) / 100;
document.getElementById('spanDeviation').innerText = (Math.round(somfy.transceiver.config.deviation * 100) / 100).fmt('#,##0.00');
document.getElementById('slidDeviation').value = Math.round(somfy.transceiver.config.deviation * 100);
document.getElementsByName('enableRadio')[0].checked = somfy.transceiver.config.enabled;
let tx = document.getElementById('slidTxPower');
let lvls = [-30, -20, -15, -10, -6, 0, 5, 7, 10, 11, 12];
@ -393,6 +396,7 @@
let valid = true;
let getIntValue = (fld) => { return parseInt(document.getElementById(fld).value, 10); }
let obj = {
enabled: document.getElementsByName('enableRadio')[0].checked,
type: parseInt(document.getElementById('selRadioType').value, 10),
SCKPin: getIntValue('selTransSCKPin'),
CSNPin: getIntValue('selTransCSNPin'),
@ -530,6 +534,7 @@
};
procRemoteFrame(frame) {
console.log(frame);
document.getElementById('spanRssi').innerHTML = frame.rssi;
let lnk = document.getElementById('divLinking');
if (lnk) {
let obj = {
@ -798,7 +803,7 @@
html += '<li>You may now press the close button</li>'
html += '</ul>'
html += `<div class="button-container">`
html += `<button id="btnSendPairing" type="button" style="padding-left:20px;padding-right:20px;display:inline-block;" onclick="sendPairCommand(${shadeId});">Prog</button>`
html += `<button id="btnSendPairing" type="button" style="padding-left:20px;padding-right:20px;display:inline-block;" onclick="somfy.sendPairCommand(${shadeId});">Prog</button>`
html += `<button id="btnStopPairing" type="button" style="padding-left:20px;padding-right:20px;display:inline-block" onclick="document.getElementById('divPairing').remove();">Close</button>`
html += `</div>`;
div.innerHTML = html;
@ -818,7 +823,7 @@
html += '<li>You may now press the close button</li>'
html += '</ul>'
html += `<div class="button-container">`
html += `<button id="btnSendUnpairing" type="button" style="padding-left:20px;padding-right:20px;display:inline-block;" onclick="sendUnpairCommand(${shadeId});">Prog</button>`
html += `<button id="btnSendUnpairing" type="button" style="padding-left:20px;padding-right:20px;display:inline-block;" onclick="somfy.sendUnpairCommand(${shadeId});">Prog</button>`
html += `<button id="btnStopUnpairing" type="button" style="padding-left:20px;padding-right:20px;display:inline-block" onclick="document.getElementById('divPairing').remove();">Close</button>`
html += `</div>`;
div.innerHTML = html;
@ -862,11 +867,10 @@
});
};
deviationChanged(el) {
document.getElementById('spanDeviation').innerText = el.value / 100;
document.getElementById('spanDeviation').innerText = (el.value / 100).fmt('#,##0.00');
};
rxBandwidthChanged(el) {
console.log(el.value);
document.getElementById('spanRxBandwidth').innerText = el.value / 100;
document.getElementById('spanRxBandwidth').innerText = (el.value / 100).fmt('#,##0.00');
};
txPowerChanged(el) {
console.log(el.value);
@ -900,7 +904,7 @@
let shadeName = elname.innerHTML;
let html = `<div class="shade-name">${shadeName}</div>`;
html += `<input id="slidShadeTarget" name="shadeTarget" type="range" min="0" max="100" step="1" value="${currPos}" onchange="somfy.processShadeTarget(this, ${shadeId});" oninput="document.getElementById('spanShadeTarget').innerHTML = this.value;" />`;
html += `<label for="shadeTarget"><span>Target Position </span><span><span id="spanShadeTarget" class="shade-target">${currPos}</span><span>%</span></span></label>`;
html += `<label for="slidShadeTarget"><span>Target Position </span><span><span id="spanShadeTarget" class="shade-target">${currPos}</span><span>%</span></span></label>`;
html += `</div>`;
let div = document.createElement('div');
div.setAttribute('class', 'shade-positioner');
@ -1041,7 +1045,7 @@
};
var firmware = new Firmware();
function setAppVersion() { document.getElementById('spanAppVersion').innerText = 'v1.0.7'; }
function setAppVersion() { document.getElementById('spanAppVersion').innerText = 'v1.0.8'; }
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 || '';
@ -1215,10 +1219,22 @@
}
xhr.send(JSON.stringify(data));
}
var socket;
var tConnect = null;
var sockIsOpen = false;
var connecting = false;
function initSockets() {
let socket = new WebSocket(`ws://${location.host}:8080`);
//let socket = new WebSocket(`ws://192.168.1.244:8080`);
if (connecting) return;
console.log('Connecting to socket...');
connecting = true;
if (tConnect) clearTimeout(tConnect);
tConnect = null;
let wms = document.getElementsByClassName('socket-wait');
for (let i = 0; i < wms.length; i++) {
wms[i].remove();
}
waitMessage(document.getElementById('divContainer')).classList.add('socket-wait');
socket = new WebSocket(`ws://${location.host}:8080`);
socket.onmessage = (evt) => {
if (evt.data.startsWith('42')) {
let ndx = evt.data.indexOf(',');
@ -1259,28 +1275,42 @@
}
}
};
let tConnect = null;
socket.onopen = (evt) => {
if (tConnect) clearTimeout(tConnect);
tConnect = null;
console.log({ msg: 'open', evt: evt });
sockIsOpen = true;
connecting = false;
let wms = document.getElementsByClassName('socket-wait');
for (let i = 0; i < wms.length; i++) {
wms[i].remove();
}
};
socket.onclose = (evt) => {
if (evt.wasClean) console.log({ msg: 'close-clean', evt: evt });
else console.log({ msg: 'close-died', evt: evt });
tConnect = setTimeout(reopenSocket, 3000);
waitMessage(document.getElementById('divContainer')).classList.add('socket-wait');
if (evt.wasClean) {
console.log({ msg: 'close-clean', evt: evt });
tConnect = setTimeout(() => { reopenSocket(); }, 10000);
console.log('Reconnecting socket in 10 seconds');
}
else {
console.log({ msg: 'close-died', reason: evt.reason, evt: evt });
tConnect = setTimeout(() => { reopenSocket(); }, 3000);
}
};
socket.onerror = (evt) => {
console.log({ msg: 'socket error', evt: evt });
}
let reopenSocket = () => {
if (tConnect) clearTimeout(tConnect);
initSockets();
}
function reopenSocket() {
if (tConnect) clearTimeout(tConnect);
tConnect = null;
initSockets();
}
</script>
</head>
<body>
<div class="container" style="user-select:none;">
<div id="divContainer" class="container" style="user-select:none;">
<h1 style="text-align: center;"><span>ESPSomfy RTS</span><span class="button-outline" onclick="general.toggleConfig();" style="float:right;font-size:1.25rem;display:inline-block;vertical-align:middle;width:38px;height:38px;position:relative;padding-top:4px;"><span style="vertical-align:middle;clear:both;text-align:center;display:inline-block;"><i id="icoConfig" class="icss-gear" style=""></i></span></span></h1>
<div id="divConfigPnl" style="display:none;">
<div style="margin-top:-10px;text-align:center;font-size:12px;">
@ -1299,20 +1329,20 @@
<legend>General Settings</legend>
<form method="post" action="/general" style="margin-top:8px;">
<div class="field-group">
<input name="hostname" type="text" length=32 placeholder="Host Name">
<label for="hostname">Host Name</label>
<input id="fldHostname" name="hostname" type="text" length=32 placeholder="Host Name">
<label for="fldHostname">Host Name</label>
</div>
<div class="field-group">
<select id="selTimeZone" name="timeZone" type="password" length=32 placeholder="Time Zone" style="width:100%;"></select>
<label for="timeZone">Time Zone</label>
<label for="selTimeZone">Time Zone</label>
</div>
<div class="field-group">
<input name="ntptimeserver" type="text" length=32 placeholder="Time Server">
<label for="ntptimeserver">NTP Time Server</label>
<input id="fldNtptimesever" name="ntptimeserver" type="text" length=32 placeholder="Time Server">
<label for="fldNtptimeserver">NTP Time Server</label>
</div>
<div class="field-group" style="vertical-align:middle;">
<input name="ssdpBroadcast" type="checkbox" style="display:inline-block;" />
<label for="ssdpBroadcast" style="display:inline-block;cursor:pointer;">Broadcast uPnP over SSDP</label>
<input id="cbSsdpBroadcast" name="ssdpBroadcast" type="checkbox" style="display:inline-block;" />
<label for="cbSsdpBroadcast" style="display:inline-block;cursor:pointer;">Broadcast uPnP over SSDP</label>
</div>
<div class="button-container">
<button id="btnSaveGeneral" type="button" onclick="general.setGeneral();">
@ -1334,12 +1364,12 @@
</form>
<form method="post" action="/wifi" style="margin-top:8px;">
<div class="field-group">
<input name="ssid" type="text" length=32 placeholder="SSID">
<label for="ssid">Network SSID</label>
<input id="fldSsid" name="ssid" type="text" length=32 placeholder="SSID">
<label for="fldSsid">Network SSID</label>
</div>
<div class="field-group">
<input name="passphrase" type="password" length=32 placeholder="Passphrase">
<label for="passphrase">Passphrase</label>
<input id="fldPassphrase" name="passphrase" type="password" length=32 placeholder="Passphrase">
<label for="fldPassphrase">Passphrase</label>
</div>
<div class="button-container">
<button id="btnConnectWiFi" type="button" onclick="wifi.connectWiFi();">
@ -1352,8 +1382,8 @@
<legend>MQTT Settings</legend>
<form method="post" action="/mqtt">
<div class="field-group" style="vertical-align:middle;">
<input name="mqtt-enabled" type="checkbox" style="display:inline-block;" />
<label for="mqtt-enabled" style="display:inline-block;cursor:pointer;">Enable MQTT client</label>
<input id="cbMqttEnabled" name="mqtt-enabled" type="checkbox" style="display:inline-block;" />
<label for="cbMqttEnabled" style="display:inline-block;cursor:pointer;">Enable MQTT client</label>
</div>
<div class="field-group1" style="white-space:nowrap;">
<select name="mqtt-protocol" style="width:54px;">
@ -1366,16 +1396,16 @@
<input name="mqtt-port" type="text" length=5 placeholder="Port" style="width:50px;">
</div>
<div class="field-group">
<input name="mqtt-username" type="text" length=32 placeholder="Username">
<label for="mqtt-username">Username</label>
<input id="fldMqttUsername" name="mqtt-username" type="text" length=32 placeholder="Username">
<label for="fldMqttUsername">Username</label>
</div>
<div class="field-group">
<input name="mqtt-password" type="text" length=64 placeholder="Password">
<label for="mqtt-password">Password</label>
<input id="fldMqttPassword" name="mqtt-password" type="text" length=64 placeholder="Password">
<label for="fldMqttPassword">Password</label>
</div>
<div class="field-group">
<input name="mqtt-topic" type="text" length=64 placeholder="Root Topic">
<label for="mqtt-topic">Root Topic</label>
<input id="fldMqttTopic" name="mqtt-topic" type="text" length=64 placeholder="Root Topic">
<label for="fldMqttTopic">Root Topic</label>
</div>
<div class="button-container">
@ -1407,8 +1437,8 @@
<div style="display:inline-block;float:right;position:relative;margin-top:-14px;"><span id="spanShadeId">*</span>/<span id="spanMaxShades">5</span></div>
<div>
<div class="field-group" style="width:127px;display:inline-block;">
<input name="shadeAddress" type="number" length=5 placeholder="Address" style="width:100%;">
<label for="shadeAddress">Remote Address</label>
<input id="fldShadeAddress" name="shadeAddress" type="number" length=5 placeholder="Address" style="width:100%;">
<label for="fldShadeAddress">Remote Address</label>
</div>
<div id="divSomfyButtons" style="float:right">
<div style="display:inline-block;padding-right:7px;"><i id="icoShade" class="somfy-shade-icon icss-window-shade" data-shadeid="0" style="--shade-position:0%;vertical-align:middle;font-size:32px;"></i></div>
@ -1418,17 +1448,17 @@
</div>
</div>
<div class="field-group">
<input name="shadeName" type="text" length=20 placeholder="Name">
<label for="shadeName">Name</label>
<input id="fldShadeName" name="shadeName" type="text" length=20 placeholder="Name">
<label for="fldShadeName">Name</label>
</div>
<div>
<div class="field-group" style="display:inline-block;max-width:127px;margin-right:17px;">
<input name="shadeUpTime" type="number" length=5 placeholder="milliseconds" style="width:100%;text-align:right;">
<label for="shadeId">Up Time (ms)</label>
<input id="fldShadeUpTime" name="shadeUpTime" type="number" length=5 placeholder="milliseconds" style="width:100%;text-align:right;">
<label for="fldShadeUpTime">Up Time (ms)</label>
</div>
<div class="field-group" style="display:inline-block;max-width:127px;">
<input name="shadeDownTime" type="number" length=5 placeholder="milliseconds" style="width:100%;text-align:right;">
<label for="shadeId">Down Time (ms)</label>
<input id="fldShadeDownTime" name="shadeDownTime" type="number" length=5 placeholder="milliseconds" style="width:100%;text-align:right;">
<label for="fldShadeDownTime">Down Time (ms)</label>
</div>
</div>
<div class="button-container" style="text-align:center;">
@ -1457,47 +1487,52 @@
</div>
<div id="somfyTransceiver" style="display:none;">
<form>
<div id="divRadioSettings" name="divRadioSettings" class="field-group1" style="white-space:nowrap;display:block;position:relative">
<div id="divRadioSettings" name="divRadioSettings" class="field-group1" style="display:block;position:relative">
<div class="field-group" style="">
<label for="selRadioType">Radio</label>
<select id="selRadioType" name="radioType" style="">
<select id="selRadioType" name="radioType" style="width:77px;">
<option value="none" selected>None</option>
<option value="56">56-BIT</option>
<option value="80">80-BIT</option>
</select>
</div>
<div class="field-group1" style="margin-top:-20px;">
<div class="field-group" style="vertical-align:middle;margin-left:7px;float:right;">
<input id="cbEnableRadio" name="enableRadio" type="checkbox" style="display:inline-block;" />
<label for="cbEnableRadio" style="display:inline-block;cursor:pointer;">Enable Radio</label>
</div>
<div class="field-group1" style="margin-top:-20px;white-space:nowrap">
<div class="field-group radioPins">
<select id="selTransSCKPin" name="transSCK"></select>
<label for="transSCK">SCLK</label>
<label for="selTransSCKPin">SCLK</label>
</div>
<div class="field-group radioPins">
<select id="selTransCSNPin" name="transCSN"></select>
<label for="transCSN">CSN</label>
<label for="selTransCSNPin">CSN</label>
</div>
<div class="field-group radioPins">
<select id="selTransMOSIPin" name="transMOSI"></select>
<label for="transMOSI">MOSI</label>
<label for="selTransMOSIPin">MOSI</label>
</div>
<div class="field-group radioPins">
<select id="selTransMISOPin" name="transMISO"></select>
<label for="transMISO">MISO</label>
<label for="selTransMISOPin">MISO</label>
</div>
</div>
<div class="field-group1" style="margin-top:-20px;">
<div class="field-group radioPins">
<select id="selTransTXPin" name="transTX"></select>
<label for="transTX">TX</label>
<label for="selTransTXPin">TX</label>
</div>
<div class="field-group radioPins">
<select id="selTransRXPin" name="transRX"></select>
<label for="transRX">RX</label>
<label for="selTransRXPin">RX</label>
</div>
</div>
<div class="field-group" style="display:inline-block;width:auto;min-width:247px;margin-top:-20px;">
<div class="field-group" style="display:inline-block;width:auto;min-width:247px;margin-top:-20px;vertical-align:top;">
<div class="field-group">
<input id="slidRxBandwidth" name="rxBandwidth" type="range" min="5803" max="81250" step="1" style="width:100%;" onchange="somfy.rxBandwidthChanged(this);" />
<label for="rxBandwidth" style="display:block;font-size:1em;margin-top:0px;margin-left:7px;">
<input id="slidRxBandwidth" name="rxBandwidth" type="range" min="5803" max="81250" step="1" style="width:100%;" oninput="somfy.rxBandwidthChanged(this);" />
<label for="slidRxBandwidth" style="display:block;font-size:1em;margin-top:0px;margin-left:7px;">
<span>RX Bandwidth </span>
<span style="float:right;display:inline-block;margin-right:7px;">
<span id="spanRxBandwidth" style="color:black;"></span><span>kHz</span>
@ -1505,12 +1540,19 @@
</label>
</div>
<div class="field-group" style="margin-top:-10px;">
<input id="slidDeviation" name="deviation" type="range" min="158" max="38085" step="1" style="width:100%;" onchange="somfy.deviationChanged(this);" />
<label for="deviation" style="display:block;font-size:1em;margin-top:0px;margin-left:7px;"><span>Frequency Deviation </span><span style="float: right; display: inline-block; margin-right: 7px;"><span id="spanDeviation" style="color:black;"></span><span>kHz</span></span></label>
<input id="slidDeviation" name="deviation" type="range" min="158" max="38085" step="1" style="width:100%;" oninput="somfy.deviationChanged(this);" />
<label for="slidDeviation" style="display:block;font-size:1em;margin-top:0px;margin-left:7px;"><span>Frequency Deviation </span><span style="float: right; display: inline-block; margin-right: 7px;"><span id="spanDeviation" style="color:black;"></span><span>kHz</span></span></label>
</div>
<div class="field-group" style="margin-top:-10px;">
<input id="slidTxPower" name="txPower" type="range" min="0" max="10" step="1" style="width:100%;" onchange="somfy.txPowerChanged(this);" />
<label for="txPower" style="display:block;font-size:1em;margin-top:0px;margin-left:7px;"><span>TX Power </span><span style="float: right; display: inline-block; margin-right: 7px;"><span id="spanTxPower" style="color:black;"></span><span>dBm</span></span></label>
<input id="slidTxPower" name="txPower" type="range" min="0" max="10" step="1" style="width:100%;" oninput="somfy.txPowerChanged(this);" />
<label for="slidTxPower" style="display:block;font-size:1em;margin-top:0px;margin-left:7px;"><span>TX Power </span><span style="float: right; display: inline-block; margin-right: 7px;"><span id="spanTxPower" style="color:black;"></span><span>dBm</span></span></label>
</div>
</div>
<div style="display:inline-block;vertical-align:top;padding-left:14px;">
<div class="field-group" style="">
<label style="display:block;width:100%;text-align:center;">RSSI</label>
<span id="spanRssi" name="rssi" style="display:block;font-size:32px;width:100%;text-align:center;">---</span>
<span style="display: block; color: #00bcd4;width:100%;text-align:center;">dBm</span>
</div>
</div>
</div>