mirror of
https://github.com/Laxilef/OTGateway.git
synced 2025-12-12 03:04:27 +05:00
Compare commits
47 Commits
1.5.4
...
14826c10cd
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
14826c10cd | ||
|
|
28a5218b7c | ||
|
|
f3ba43adbd | ||
|
|
062c6714d1 | ||
|
|
502f73db0e | ||
|
|
c2ee30d1ab | ||
|
|
9217bb7448 | ||
|
|
d694ae18c0 | ||
|
|
0f4fa2e406 | ||
|
|
df2af928a5 | ||
|
|
3e6a2d93d4 | ||
|
|
062468c6b1 | ||
|
|
530892dc09 | ||
|
|
c73f74ad45 | ||
|
|
a67ff046b0 | ||
|
|
0f496fee42 | ||
|
|
e63a0dc7eb | ||
|
|
792c6a6668 | ||
|
|
94f6f14795 | ||
|
|
47696a0721 | ||
|
|
5c4ad8cd07 | ||
|
|
f6cfdf3263 | ||
|
|
58b0c18448 | ||
|
|
b985275309 | ||
|
|
1eee184887 | ||
|
|
ba03c9cda3 | ||
|
|
14b1eac732 | ||
|
|
d16f56d280 | ||
|
|
8b50ed48c1 | ||
|
|
f212d9d9a8 | ||
|
|
0e78e71493 | ||
|
|
655313562d | ||
|
|
c8e7724da8 | ||
|
|
f986129c72 | ||
|
|
7b31315242 | ||
|
|
6872cad8ce | ||
|
|
4b1b7f5857 | ||
|
|
a667317412 | ||
|
|
612b17b86f | ||
|
|
7c032ddc2f | ||
|
|
9dd5ee8da5 | ||
|
|
7dbd503e1e | ||
|
|
85932fdc1d | ||
|
|
77d80225ad | ||
|
|
dc68315166 | ||
|
|
5d0ca68dc0 | ||
|
|
d50b70c211 |
2
.github/workflows/pio-dependabot.yaml
vendored
2
.github/workflows/pio-dependabot.yaml
vendored
@@ -15,7 +15,7 @@ jobs:
|
|||||||
name: run PlatformIO Dependabot
|
name: run PlatformIO Dependabot
|
||||||
steps:
|
steps:
|
||||||
- name: Checkout
|
- name: Checkout
|
||||||
uses: actions/checkout@v4
|
uses: actions/checkout@v5
|
||||||
- name: run PlatformIO Dependabot
|
- name: run PlatformIO Dependabot
|
||||||
uses: peterus/platformio_dependabot@v1.2.0
|
uses: peterus/platformio_dependabot@v1.2.0
|
||||||
with:
|
with:
|
||||||
|
|||||||
2
.github/workflows/stale.yaml
vendored
2
.github/workflows/stale.yaml
vendored
@@ -7,7 +7,7 @@ jobs:
|
|||||||
stale:
|
stale:
|
||||||
runs-on: ubuntu-latest
|
runs-on: ubuntu-latest
|
||||||
steps:
|
steps:
|
||||||
- uses: actions/stale@v9
|
- uses: actions/stale@v10
|
||||||
with:
|
with:
|
||||||
stale-issue-message: >
|
stale-issue-message: >
|
||||||
This issue is stale because it has been open 15 days with no activity. Remove stale label or comment or this will be closed in 5 days.
|
This issue is stale because it has been open 15 days with no activity. Remove stale label or comment or this will be closed in 5 days.
|
||||||
|
|||||||
1
.gitignore
vendored
1
.gitignore
vendored
@@ -1,5 +1,6 @@
|
|||||||
.pio
|
.pio
|
||||||
.vscode
|
.vscode
|
||||||
|
.PVS-Studio
|
||||||
build/*
|
build/*
|
||||||
data/*
|
data/*
|
||||||
managed_components/*
|
managed_components/*
|
||||||
|
|||||||
@@ -71,5 +71,10 @@ All available information and instructions can be found in the wiki:
|
|||||||
* [Connection](https://github.com/Laxilef/OTGateway/wiki/OT-adapters#connection)
|
* [Connection](https://github.com/Laxilef/OTGateway/wiki/OT-adapters#connection)
|
||||||
* [Leds on board](https://github.com/Laxilef/OTGateway/wiki/OT-adapters#leds-on-board)
|
* [Leds on board](https://github.com/Laxilef/OTGateway/wiki/OT-adapters#leds-on-board)
|
||||||
|
|
||||||
___
|
## Gratitude
|
||||||
This project is tested with BrowserStack.
|
* To the developers of the libraries used: [OpenTherm Library](https://github.com/ihormelnyk/opentherm_library), [ESP8266Scheduler](https://github.com/nrwiersma/ESP8266Scheduler), [ArduinoJson](https://github.com/bblanchon/ArduinoJson), [NimBLE-Arduino](https://github.com/h2zero/NimBLE-Arduino), [ArduinoMqttClient](https://github.com/arduino-libraries/ArduinoMqttClient), [ESPTelnet](https://github.com/LennartHennigs/ESPTelnet), [FileData](https://github.com/GyverLibs/FileData), [GyverPID](https://github.com/GyverLibs/GyverPID), [GyverBlinker](https://github.com/GyverLibs/GyverBlinker), [OneWireNg](https://github.com/pstolarz/OneWireNg) & [OneWire](https://github.com/PaulStoffregen/OneWire)
|
||||||
|
* To the [PlatformIO](https://platformio.org/) Team
|
||||||
|
* To the team and contributors of the [pioarduino](https://github.com/pioarduino/platform-espressif32) project
|
||||||
|
* To the [BrowserStack](https://www.browserstack.com/) team. This project is tested with BrowserStack.
|
||||||
|
* To the [PVS-Studio](https://pvs-studio.com/pvs-studio/?utm_source=website&utm_medium=github&utm_campaign=open_source) - static analyzer for C, C++, C#, and Java code.
|
||||||
|
* And of course to the contributors for their contribution to the development of the project!
|
||||||
@@ -4,10 +4,10 @@
|
|||||||
class CustomOpenTherm : public OpenTherm {
|
class CustomOpenTherm : public OpenTherm {
|
||||||
public:
|
public:
|
||||||
typedef std::function<void(unsigned int)> DelayCallback;
|
typedef std::function<void(unsigned int)> DelayCallback;
|
||||||
typedef std::function<void(unsigned long, byte)> BeforeSendRequestCallback;
|
typedef std::function<void(unsigned long, uint8_t)> BeforeSendRequestCallback;
|
||||||
typedef std::function<void(unsigned long, unsigned long, OpenThermResponseStatus, byte)> AfterSendRequestCallback;
|
typedef std::function<void(unsigned long, unsigned long, OpenThermResponseStatus, uint8_t)> AfterSendRequestCallback;
|
||||||
|
|
||||||
CustomOpenTherm(int inPin = 4, int outPin = 5, bool isSlave = false) : OpenTherm(inPin, outPin, isSlave) {}
|
CustomOpenTherm(int inPin = 4, int outPin = 5, bool isSlave = false, bool alwaysReceive = false) : OpenTherm(inPin, outPin, isSlave, alwaysReceive) {}
|
||||||
~CustomOpenTherm() {}
|
~CustomOpenTherm() {}
|
||||||
|
|
||||||
CustomOpenTherm* setDelayCallback(DelayCallback callback = nullptr) {
|
CustomOpenTherm* setDelayCallback(DelayCallback callback = nullptr) {
|
||||||
@@ -28,8 +28,8 @@ public:
|
|||||||
return this;
|
return this;
|
||||||
}
|
}
|
||||||
|
|
||||||
unsigned long sendRequest(unsigned long request, byte attempts = 5, byte _attempt = 0) {
|
unsigned long sendRequest(unsigned long request) override {
|
||||||
_attempt++;
|
this->sendRequestAttempt++;
|
||||||
|
|
||||||
while (!this->isReady()) {
|
while (!this->isReady()) {
|
||||||
if (this->delayCallback) {
|
if (this->delayCallback) {
|
||||||
@@ -40,15 +40,10 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (this->beforeSendRequestCallback) {
|
if (this->beforeSendRequestCallback) {
|
||||||
this->beforeSendRequestCallback(request, _attempt);
|
this->beforeSendRequestCallback(request, this->sendRequestAttempt);
|
||||||
}
|
}
|
||||||
|
|
||||||
unsigned long _response;
|
if (this->sendRequestAsync(request)) {
|
||||||
OpenThermResponseStatus _responseStatus = OpenThermResponseStatus::NONE;
|
|
||||||
if (!this->sendRequestAsync(request)) {
|
|
||||||
_response = 0;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
do {
|
do {
|
||||||
if (this->delayCallback) {
|
if (this->delayCallback) {
|
||||||
this->delayCallback(150);
|
this->delayCallback(150);
|
||||||
@@ -56,42 +51,25 @@ public:
|
|||||||
|
|
||||||
this->process();
|
this->process();
|
||||||
} while (this->status != OpenThermStatus::READY && this->status != OpenThermStatus::DELAY);
|
} while (this->status != OpenThermStatus::READY && this->status != OpenThermStatus::DELAY);
|
||||||
|
|
||||||
_response = this->getLastResponse();
|
|
||||||
_responseStatus = this->getLastResponseStatus();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (this->afterSendRequestCallback) {
|
if (this->afterSendRequestCallback) {
|
||||||
this->afterSendRequestCallback(request, _response, _responseStatus, _attempt);
|
this->afterSendRequestCallback(request, this->response, this->responseStatus, this->sendRequestAttempt);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (_responseStatus == OpenThermResponseStatus::SUCCESS || _responseStatus == OpenThermResponseStatus::INVALID || _attempt >= attempts) {
|
if (this->responseStatus == OpenThermResponseStatus::SUCCESS || this->responseStatus == OpenThermResponseStatus::INVALID) {
|
||||||
return _response;
|
this->sendRequestAttempt = 0;
|
||||||
|
return this->response;
|
||||||
|
|
||||||
|
} else if (this->sendRequestAttempt >= this->sendRequestMaxAttempts) {
|
||||||
|
this->sendRequestAttempt = 0;
|
||||||
|
return this->response;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
return this->sendRequest(request, attempts, _attempt);
|
return this->sendRequest(request);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
unsigned long setBoilerStatus(bool enableCentralHeating, bool enableHotWater, bool enableCooling, bool enableOutsideTemperatureCompensation, bool enableCentralHeating2, bool summerWinterMode, bool dhwBlocking, uint8_t lb = 0) {
|
|
||||||
unsigned int data = enableCentralHeating
|
|
||||||
| (enableHotWater << 1)
|
|
||||||
| (enableCooling << 2)
|
|
||||||
| (enableOutsideTemperatureCompensation << 3)
|
|
||||||
| (enableCentralHeating2 << 4)
|
|
||||||
| (summerWinterMode << 5)
|
|
||||||
| (dhwBlocking << 6);
|
|
||||||
|
|
||||||
data <<= 8;
|
|
||||||
data |= lb;
|
|
||||||
|
|
||||||
return this->sendRequest(buildRequest(
|
|
||||||
OpenThermMessageType::READ_DATA,
|
|
||||||
OpenThermMessageID::Status,
|
|
||||||
data
|
|
||||||
));
|
|
||||||
}
|
|
||||||
|
|
||||||
bool sendBoilerReset() {
|
bool sendBoilerReset() {
|
||||||
unsigned int data = 1;
|
unsigned int data = 1;
|
||||||
data <<= 8;
|
data <<= 8;
|
||||||
@@ -128,10 +106,35 @@ public:
|
|||||||
return isValidResponse(response) && isValidResponseId(response, OpenThermMessageID::RemoteRequest);
|
return isValidResponse(response) && isValidResponseId(response, OpenThermMessageID::RemoteRequest);
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool isValidResponseId(unsigned long response, OpenThermMessageID id) {
|
static bool isCh2Active(unsigned long response) {
|
||||||
byte responseId = (response >> 16) & 0xFF;
|
return response & 0x20;
|
||||||
|
}
|
||||||
|
|
||||||
return (byte)id == responseId;
|
static bool isValidResponseId(unsigned long response, OpenThermMessageID id) {
|
||||||
|
uint8_t responseId = (response >> 16) & 0xFF;
|
||||||
|
|
||||||
|
return (uint8_t)id == responseId;
|
||||||
|
}
|
||||||
|
|
||||||
|
static uint8_t getResponseMessageTypeId(unsigned long response) {
|
||||||
|
return (response << 1) >> 29;
|
||||||
|
}
|
||||||
|
|
||||||
|
static const char* getResponseMessageTypeString(unsigned long response) {
|
||||||
|
uint8_t msgType = getResponseMessageTypeId(response);
|
||||||
|
|
||||||
|
switch (msgType) {
|
||||||
|
case (uint8_t) OpenThermMessageType::READ_ACK:
|
||||||
|
case (uint8_t) OpenThermMessageType::WRITE_ACK:
|
||||||
|
case (uint8_t) OpenThermMessageType::DATA_INVALID:
|
||||||
|
case (uint8_t) OpenThermMessageType::UNKNOWN_DATA_ID:
|
||||||
|
return CustomOpenTherm::messageTypeToString(
|
||||||
|
static_cast<OpenThermMessageType>(msgType)
|
||||||
|
);
|
||||||
|
|
||||||
|
default:
|
||||||
|
return "UNKNOWN";
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// converters
|
// converters
|
||||||
@@ -145,6 +148,8 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
const uint8_t sendRequestMaxAttempts = 5;
|
||||||
|
uint8_t sendRequestAttempt = 0;
|
||||||
DelayCallback delayCallback;
|
DelayCallback delayCallback;
|
||||||
BeforeSendRequestCallback beforeSendRequestCallback;
|
BeforeSendRequestCallback beforeSendRequestCallback;
|
||||||
AfterSendRequestCallback afterSendRequestCallback;
|
AfterSendRequestCallback afterSendRequestCallback;
|
||||||
|
|||||||
@@ -35,7 +35,7 @@ namespace NetworkUtils {
|
|||||||
return this;
|
return this;
|
||||||
}
|
}
|
||||||
|
|
||||||
NetworkMgr* setApCredentials(const char* ssid, const char* password = nullptr, byte channel = 0) {
|
NetworkMgr* setApCredentials(const char* ssid, const char* password = nullptr, uint8_t channel = 0) {
|
||||||
this->apName = ssid;
|
this->apName = ssid;
|
||||||
this->apPassword = password;
|
this->apPassword = password;
|
||||||
this->apChannel = channel;
|
this->apChannel = channel;
|
||||||
@@ -43,7 +43,7 @@ namespace NetworkUtils {
|
|||||||
return this;
|
return this;
|
||||||
}
|
}
|
||||||
|
|
||||||
NetworkMgr* setStaCredentials(const char* ssid = nullptr, const char* password = nullptr, byte channel = 0) {
|
NetworkMgr* setStaCredentials(const char* ssid = nullptr, const char* password = nullptr, uint8_t channel = 0) {
|
||||||
this->staSsid = ssid;
|
this->staSsid = ssid;
|
||||||
this->staPassword = password;
|
this->staPassword = password;
|
||||||
this->staChannel = channel;
|
this->staChannel = channel;
|
||||||
@@ -140,7 +140,7 @@ namespace NetworkUtils {
|
|||||||
return this->staPassword;
|
return this->staPassword;
|
||||||
}
|
}
|
||||||
|
|
||||||
byte getStaChannel() {
|
uint8_t getStaChannel() {
|
||||||
return this->staChannel;
|
return this->staChannel;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -377,7 +377,7 @@ namespace NetworkUtils {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static byte rssiToSignalQuality(short int rssi) {
|
static uint8_t rssiToSignalQuality(short int rssi) {
|
||||||
return constrain(map(rssi, -100, -50, 0, 100), 0, 100);
|
return constrain(map(rssi, -100, -50, 0, 100), 0, 100);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -397,11 +397,11 @@ namespace NetworkUtils {
|
|||||||
const char* hostname = "esp";
|
const char* hostname = "esp";
|
||||||
const char* apName = "ESP";
|
const char* apName = "ESP";
|
||||||
const char* apPassword = nullptr;
|
const char* apPassword = nullptr;
|
||||||
byte apChannel = 1;
|
uint8_t apChannel = 1;
|
||||||
|
|
||||||
const char* staSsid = nullptr;
|
const char* staSsid = nullptr;
|
||||||
const char* staPassword = nullptr;
|
const char* staPassword = nullptr;
|
||||||
byte staChannel = 0;
|
uint8_t staChannel = 0;
|
||||||
|
|
||||||
bool useDhcp = true;
|
bool useDhcp = true;
|
||||||
IPAddress staticIp;
|
IPAddress staticIp;
|
||||||
|
|||||||
@@ -14,15 +14,15 @@ extra_configs = secrets.default.ini
|
|||||||
core_dir = .pio
|
core_dir = .pio
|
||||||
|
|
||||||
[env]
|
[env]
|
||||||
version = 1.5.4
|
version = 1.5.6
|
||||||
framework = arduino
|
framework = arduino
|
||||||
lib_deps =
|
lib_deps =
|
||||||
bblanchon/ArduinoJson@^7.3.0
|
bblanchon/ArduinoJson@^7.4.2
|
||||||
;ihormelnyk/OpenTherm Library@^1.1.5
|
;ihormelnyk/OpenTherm Library@^1.1.5
|
||||||
https://github.com/ihormelnyk/opentherm_library#master
|
https://github.com/Laxilef/opentherm_library#esp32_timer
|
||||||
arduino-libraries/ArduinoMqttClient@^0.1.8
|
arduino-libraries/ArduinoMqttClient@^0.1.8
|
||||||
lennarthennigs/ESP Telnet@^2.2
|
lennarthennigs/ESP Telnet@^2.2.3
|
||||||
gyverlibs/FileData@^1.0.2
|
gyverlibs/FileData@^1.0.3
|
||||||
gyverlibs/GyverPID@^3.3.2
|
gyverlibs/GyverPID@^3.3.2
|
||||||
gyverlibs/GyverBlinker@^1.1.1
|
gyverlibs/GyverBlinker@^1.1.1
|
||||||
https://github.com/pstolarz/Arduino-Temperature-Control-Library.git#OneWireNg
|
https://github.com/pstolarz/Arduino-Temperature-Control-Library.git#OneWireNg
|
||||||
@@ -60,10 +60,16 @@ monitor_filters =
|
|||||||
esp8266_exception_decoder
|
esp8266_exception_decoder
|
||||||
board_build.flash_mode = dio
|
board_build.flash_mode = dio
|
||||||
board_build.filesystem = littlefs
|
board_build.filesystem = littlefs
|
||||||
|
check_tool = ; pvs-studio
|
||||||
|
check_flags =
|
||||||
|
; pvs-studio:
|
||||||
|
; --analysis-mode=4
|
||||||
|
; --exclude-path=./.pio/libdeps
|
||||||
|
|
||||||
; Defaults
|
; Defaults
|
||||||
[esp8266_defaults]
|
[esp8266_defaults]
|
||||||
platform = espressif8266@^4.2.1
|
platform = espressif8266@^4.2.1
|
||||||
|
platform_packages = ${env.platform_packages}
|
||||||
lib_deps =
|
lib_deps =
|
||||||
${env.lib_deps}
|
${env.lib_deps}
|
||||||
nrwiersma/ESP8266Scheduler@^1.2
|
nrwiersma/ESP8266Scheduler@^1.2
|
||||||
@@ -77,6 +83,8 @@ build_flags =
|
|||||||
;-D PIO_FRAMEWORK_ARDUINO_LWIP2_HIGHER_BANDWIDTH_LOW_FLASH
|
;-D PIO_FRAMEWORK_ARDUINO_LWIP2_HIGHER_BANDWIDTH_LOW_FLASH
|
||||||
-D PIO_FRAMEWORK_ARDUINO_ESPRESSIF_SDK305
|
-D PIO_FRAMEWORK_ARDUINO_ESPRESSIF_SDK305
|
||||||
board_build.ldscript = eagle.flash.4m1m.ld
|
board_build.ldscript = eagle.flash.4m1m.ld
|
||||||
|
check_tool = ${env.check_tool}
|
||||||
|
check_flags = ${env.check_flags}
|
||||||
|
|
||||||
[esp32_defaults]
|
[esp32_defaults]
|
||||||
;platform = espressif32@^6.7
|
;platform = espressif32@^6.7
|
||||||
@@ -84,13 +92,13 @@ board_build.ldscript = eagle.flash.4m1m.ld
|
|||||||
;platform_packages =
|
;platform_packages =
|
||||||
; framework-arduinoespressif32 @ https://github.com/espressif/arduino-esp32.git#3.0.5
|
; framework-arduinoespressif32 @ https://github.com/espressif/arduino-esp32.git#3.0.5
|
||||||
; framework-arduinoespressif32-libs @ https://github.com/espressif/esp32-arduino-lib-builder/releases/download/idf-release_v5.1/esp32-arduino-libs-idf-release_v5.1-33fbade6.zip
|
; framework-arduinoespressif32-libs @ https://github.com/espressif/esp32-arduino-lib-builder/releases/download/idf-release_v5.1/esp32-arduino-libs-idf-release_v5.1-33fbade6.zip
|
||||||
platform = https://github.com/pioarduino/platform-espressif32/releases/download/53.03.13/platform-espressif32.zip
|
platform = https://github.com/pioarduino/platform-espressif32/releases/download/55.03.31/platform-espressif32.zip
|
||||||
platform_packages =
|
platform_packages = ${env.platform_packages}
|
||||||
board_build.partitions = esp32_partitions.csv
|
board_build.partitions = esp32_partitions.csv
|
||||||
lib_deps =
|
lib_deps =
|
||||||
${env.lib_deps}
|
${env.lib_deps}
|
||||||
laxilef/ESP32Scheduler@^1.0.1
|
laxilef/ESP32Scheduler@^1.0.1
|
||||||
nimble_lib = h2zero/NimBLE-Arduino@^2.1.0
|
nimble_lib = h2zero/NimBLE-Arduino@^2.3.6
|
||||||
lib_ignore =
|
lib_ignore =
|
||||||
extra_scripts =
|
extra_scripts =
|
||||||
post:tools/esp32.py
|
post:tools/esp32.py
|
||||||
@@ -100,11 +108,14 @@ build_flags =
|
|||||||
${env.build_flags}
|
${env.build_flags}
|
||||||
-D CORE_DEBUG_LEVEL=0
|
-D CORE_DEBUG_LEVEL=0
|
||||||
-Wl,--wrap=esp_panic_handler
|
-Wl,--wrap=esp_panic_handler
|
||||||
|
check_tool = ${env.check_tool}
|
||||||
|
check_flags = ${env.check_flags}
|
||||||
|
|
||||||
|
|
||||||
; Boards
|
; Boards
|
||||||
[env:d1_mini]
|
[env:d1_mini]
|
||||||
platform = ${esp8266_defaults.platform}
|
platform = ${esp8266_defaults.platform}
|
||||||
|
platform_packages = ${esp8266_defaults.platform_packages}
|
||||||
board = d1_mini
|
board = d1_mini
|
||||||
lib_deps = ${esp8266_defaults.lib_deps}
|
lib_deps = ${esp8266_defaults.lib_deps}
|
||||||
lib_ignore = ${esp8266_defaults.lib_ignore}
|
lib_ignore = ${esp8266_defaults.lib_ignore}
|
||||||
@@ -119,9 +130,12 @@ build_flags =
|
|||||||
-D DEFAULT_SENSOR_INDOOR_GPIO=14
|
-D DEFAULT_SENSOR_INDOOR_GPIO=14
|
||||||
-D DEFAULT_STATUS_LED_GPIO=13
|
-D DEFAULT_STATUS_LED_GPIO=13
|
||||||
-D DEFAULT_OT_RX_LED_GPIO=15
|
-D DEFAULT_OT_RX_LED_GPIO=15
|
||||||
|
check_tool = ${esp8266_defaults.check_tool}
|
||||||
|
check_flags = ${esp8266_defaults.check_flags}
|
||||||
|
|
||||||
[env:d1_mini_lite]
|
[env:d1_mini_lite]
|
||||||
platform = ${esp8266_defaults.platform}
|
platform = ${esp8266_defaults.platform}
|
||||||
|
platform_packages = ${esp8266_defaults.platform_packages}
|
||||||
board = d1_mini_lite
|
board = d1_mini_lite
|
||||||
lib_deps = ${esp8266_defaults.lib_deps}
|
lib_deps = ${esp8266_defaults.lib_deps}
|
||||||
lib_ignore = ${esp8266_defaults.lib_ignore}
|
lib_ignore = ${esp8266_defaults.lib_ignore}
|
||||||
@@ -136,9 +150,12 @@ build_flags =
|
|||||||
-D DEFAULT_SENSOR_INDOOR_GPIO=14
|
-D DEFAULT_SENSOR_INDOOR_GPIO=14
|
||||||
-D DEFAULT_STATUS_LED_GPIO=13
|
-D DEFAULT_STATUS_LED_GPIO=13
|
||||||
-D DEFAULT_OT_RX_LED_GPIO=15
|
-D DEFAULT_OT_RX_LED_GPIO=15
|
||||||
|
check_tool = ${esp8266_defaults.check_tool}
|
||||||
|
check_flags = ${esp8266_defaults.check_flags}
|
||||||
|
|
||||||
[env:d1_mini_pro]
|
[env:d1_mini_pro]
|
||||||
platform = ${esp8266_defaults.platform}
|
platform = ${esp8266_defaults.platform}
|
||||||
|
platform_packages = ${esp8266_defaults.platform_packages}
|
||||||
board = d1_mini_pro
|
board = d1_mini_pro
|
||||||
lib_deps = ${esp8266_defaults.lib_deps}
|
lib_deps = ${esp8266_defaults.lib_deps}
|
||||||
lib_ignore = ${esp8266_defaults.lib_ignore}
|
lib_ignore = ${esp8266_defaults.lib_ignore}
|
||||||
@@ -153,9 +170,12 @@ build_flags =
|
|||||||
-D DEFAULT_SENSOR_INDOOR_GPIO=14
|
-D DEFAULT_SENSOR_INDOOR_GPIO=14
|
||||||
-D DEFAULT_STATUS_LED_GPIO=13
|
-D DEFAULT_STATUS_LED_GPIO=13
|
||||||
-D DEFAULT_OT_RX_LED_GPIO=15
|
-D DEFAULT_OT_RX_LED_GPIO=15
|
||||||
|
check_tool = ${esp8266_defaults.check_tool}
|
||||||
|
check_flags = ${esp8266_defaults.check_flags}
|
||||||
|
|
||||||
[env:nodemcu_8266]
|
[env:nodemcu_8266]
|
||||||
platform = ${esp8266_defaults.platform}
|
platform = ${esp8266_defaults.platform}
|
||||||
|
platform_packages = ${esp8266_defaults.platform_packages}
|
||||||
board = nodemcuv2
|
board = nodemcuv2
|
||||||
lib_deps = ${esp8266_defaults.lib_deps}
|
lib_deps = ${esp8266_defaults.lib_deps}
|
||||||
lib_ignore = ${esp8266_defaults.lib_ignore}
|
lib_ignore = ${esp8266_defaults.lib_ignore}
|
||||||
@@ -170,6 +190,8 @@ build_flags =
|
|||||||
-D DEFAULT_SENSOR_INDOOR_GPIO=4
|
-D DEFAULT_SENSOR_INDOOR_GPIO=4
|
||||||
-D DEFAULT_STATUS_LED_GPIO=2
|
-D DEFAULT_STATUS_LED_GPIO=2
|
||||||
-D DEFAULT_OT_RX_LED_GPIO=16
|
-D DEFAULT_OT_RX_LED_GPIO=16
|
||||||
|
check_tool = ${esp8266_defaults.check_tool}
|
||||||
|
check_flags = ${esp8266_defaults.check_flags}
|
||||||
|
|
||||||
[env:s2_mini]
|
[env:s2_mini]
|
||||||
platform = ${esp32_defaults.platform}
|
platform = ${esp32_defaults.platform}
|
||||||
@@ -192,6 +214,8 @@ build_flags =
|
|||||||
-D DEFAULT_SENSOR_INDOOR_GPIO=7
|
-D DEFAULT_SENSOR_INDOOR_GPIO=7
|
||||||
-D DEFAULT_STATUS_LED_GPIO=11
|
-D DEFAULT_STATUS_LED_GPIO=11
|
||||||
-D DEFAULT_OT_RX_LED_GPIO=12
|
-D DEFAULT_OT_RX_LED_GPIO=12
|
||||||
|
check_tool = ${esp32_defaults.check_tool}
|
||||||
|
check_flags = ${esp32_defaults.check_flags}
|
||||||
|
|
||||||
[env:s3_mini]
|
[env:s3_mini]
|
||||||
platform = ${esp32_defaults.platform}
|
platform = ${esp32_defaults.platform}
|
||||||
@@ -218,6 +242,8 @@ build_flags =
|
|||||||
-D DEFAULT_SENSOR_INDOOR_GPIO=12
|
-D DEFAULT_SENSOR_INDOOR_GPIO=12
|
||||||
-D DEFAULT_STATUS_LED_GPIO=11
|
-D DEFAULT_STATUS_LED_GPIO=11
|
||||||
-D DEFAULT_OT_RX_LED_GPIO=10
|
-D DEFAULT_OT_RX_LED_GPIO=10
|
||||||
|
check_tool = ${esp32_defaults.check_tool}
|
||||||
|
check_flags = ${esp32_defaults.check_flags}
|
||||||
|
|
||||||
[env:c3_mini]
|
[env:c3_mini]
|
||||||
platform = ${esp32_defaults.platform}
|
platform = ${esp32_defaults.platform}
|
||||||
@@ -242,6 +268,8 @@ build_flags =
|
|||||||
-D DEFAULT_SENSOR_INDOOR_GPIO=1
|
-D DEFAULT_SENSOR_INDOOR_GPIO=1
|
||||||
-D DEFAULT_STATUS_LED_GPIO=4
|
-D DEFAULT_STATUS_LED_GPIO=4
|
||||||
-D DEFAULT_OT_RX_LED_GPIO=5
|
-D DEFAULT_OT_RX_LED_GPIO=5
|
||||||
|
check_tool = ${esp32_defaults.check_tool}
|
||||||
|
check_flags = ${esp32_defaults.check_flags}
|
||||||
|
|
||||||
[env:nodemcu_32]
|
[env:nodemcu_32]
|
||||||
platform = ${esp32_defaults.platform}
|
platform = ${esp32_defaults.platform}
|
||||||
@@ -263,6 +291,12 @@ build_flags =
|
|||||||
-D DEFAULT_SENSOR_INDOOR_GPIO=26
|
-D DEFAULT_SENSOR_INDOOR_GPIO=26
|
||||||
-D DEFAULT_STATUS_LED_GPIO=2
|
-D DEFAULT_STATUS_LED_GPIO=2
|
||||||
-D DEFAULT_OT_RX_LED_GPIO=19
|
-D DEFAULT_OT_RX_LED_GPIO=19
|
||||||
|
check_tool = ${esp32_defaults.check_tool}
|
||||||
|
check_flags = ${esp32_defaults.check_flags}
|
||||||
|
|
||||||
|
[env:nodemcu_32_160mhz]
|
||||||
|
extends = env:nodemcu_32
|
||||||
|
board_build.f_cpu = 160000000L ; set frequency to 160MHz
|
||||||
|
|
||||||
[env:d1_mini32]
|
[env:d1_mini32]
|
||||||
platform = ${esp32_defaults.platform}
|
platform = ${esp32_defaults.platform}
|
||||||
@@ -284,6 +318,8 @@ build_flags =
|
|||||||
-D DEFAULT_SENSOR_INDOOR_GPIO=18
|
-D DEFAULT_SENSOR_INDOOR_GPIO=18
|
||||||
-D DEFAULT_STATUS_LED_GPIO=2
|
-D DEFAULT_STATUS_LED_GPIO=2
|
||||||
-D DEFAULT_OT_RX_LED_GPIO=19
|
-D DEFAULT_OT_RX_LED_GPIO=19
|
||||||
|
check_tool = ${esp32_defaults.check_tool}
|
||||||
|
check_flags = ${esp32_defaults.check_flags}
|
||||||
|
|
||||||
[env:esp32_c6]
|
[env:esp32_c6]
|
||||||
platform = ${esp32_defaults.platform}
|
platform = ${esp32_defaults.platform}
|
||||||
@@ -291,6 +327,11 @@ framework = arduino, espidf
|
|||||||
platform_packages = ${esp32_defaults.platform_packages}
|
platform_packages = ${esp32_defaults.platform_packages}
|
||||||
board = esp32-c6-devkitm-1
|
board = esp32-c6-devkitm-1
|
||||||
board_build.partitions = ${esp32_defaults.board_build.partitions}
|
board_build.partitions = ${esp32_defaults.board_build.partitions}
|
||||||
|
board_build.embed_txtfiles =
|
||||||
|
managed_components/espressif__esp_insights/server_certs/https_server.crt
|
||||||
|
managed_components/espressif__esp_rainmaker/server_certs/rmaker_mqtt_server.crt
|
||||||
|
managed_components/espressif__esp_rainmaker/server_certs/rmaker_claim_service_server.crt
|
||||||
|
managed_components/espressif__esp_rainmaker/server_certs/rmaker_ota_server.crt
|
||||||
lib_deps = ${esp32_defaults.lib_deps}
|
lib_deps = ${esp32_defaults.lib_deps}
|
||||||
lib_ignore =
|
lib_ignore =
|
||||||
${esp32_defaults.lib_ignore}
|
${esp32_defaults.lib_ignore}
|
||||||
@@ -307,6 +348,8 @@ build_flags =
|
|||||||
-D DEFAULT_SENSOR_INDOOR_GPIO=0
|
-D DEFAULT_SENSOR_INDOOR_GPIO=0
|
||||||
-D DEFAULT_STATUS_LED_GPIO=11
|
-D DEFAULT_STATUS_LED_GPIO=11
|
||||||
-D DEFAULT_OT_RX_LED_GPIO=10
|
-D DEFAULT_OT_RX_LED_GPIO=10
|
||||||
|
check_tool = ${esp32_defaults.check_tool}
|
||||||
|
check_flags = ${esp32_defaults.check_flags}
|
||||||
|
|
||||||
[env:otthing]
|
[env:otthing]
|
||||||
platform = ${esp32_defaults.platform}
|
platform = ${esp32_defaults.platform}
|
||||||
@@ -332,3 +375,5 @@ build_flags =
|
|||||||
-D DEFAULT_STATUS_LED_GPIO=8
|
-D DEFAULT_STATUS_LED_GPIO=8
|
||||||
-D DEFAULT_OT_RX_LED_GPIO=2
|
-D DEFAULT_OT_RX_LED_GPIO=2
|
||||||
-D OT_BYPASS_RELAY_GPIO=20
|
-D OT_BYPASS_RELAY_GPIO=20
|
||||||
|
check_tool = ${esp32_defaults.check_tool}
|
||||||
|
check_flags = ${esp32_defaults.check_flags}
|
||||||
|
|||||||
@@ -3,8 +3,8 @@
|
|||||||
|
|
||||||
class HaHelper : public HomeAssistantHelper {
|
class HaHelper : public HomeAssistantHelper {
|
||||||
public:
|
public:
|
||||||
static const byte TEMP_SOURCE_HEATING = 0;
|
static const uint8_t TEMP_SOURCE_HEATING = 0;
|
||||||
static const byte TEMP_SOURCE_INDOOR = 1;
|
static const uint8_t TEMP_SOURCE_INDOOR = 1;
|
||||||
static const char AVAILABILITY_OT_CONN[];
|
static const char AVAILABILITY_OT_CONN[];
|
||||||
static const char AVAILABILITY_SENSOR_CONN[];
|
static const char AVAILABILITY_SENSOR_CONN[];
|
||||||
|
|
||||||
@@ -395,7 +395,7 @@ public:
|
|||||||
doc[FPSTR(HA_AVAILABILITY)][FPSTR(HA_TOPIC)] = this->statusTopic.c_str();
|
doc[FPSTR(HA_AVAILABILITY)][FPSTR(HA_TOPIC)] = this->statusTopic.c_str();
|
||||||
doc[FPSTR(HA_ENABLED_BY_DEFAULT)] = enabledByDefault;
|
doc[FPSTR(HA_ENABLED_BY_DEFAULT)] = enabledByDefault;
|
||||||
doc[FPSTR(HA_ENTITY_CATEGORY)] = FPSTR(HA_ENTITY_CATEGORY_DIAGNOSTIC);
|
doc[FPSTR(HA_ENTITY_CATEGORY)] = FPSTR(HA_ENTITY_CATEGORY_DIAGNOSTIC);
|
||||||
doc[FPSTR(HA_DEVICE_CLASS)] = F("signal_strength");
|
//doc[FPSTR(HA_DEVICE_CLASS)] = F("signal_strength");
|
||||||
doc[FPSTR(HA_STATE_CLASS)] = FPSTR(HA_STATE_CLASS_MEASUREMENT);
|
doc[FPSTR(HA_STATE_CLASS)] = FPSTR(HA_STATE_CLASS_MEASUREMENT);
|
||||||
doc[FPSTR(HA_UNIT_OF_MEASUREMENT)] = FPSTR(HA_UNIT_OF_MEASUREMENT_PERCENT);
|
doc[FPSTR(HA_UNIT_OF_MEASUREMENT)] = FPSTR(HA_UNIT_OF_MEASUREMENT_PERCENT);
|
||||||
doc[FPSTR(HA_ICON)] = F("mdi:signal");
|
doc[FPSTR(HA_ICON)] = F("mdi:signal");
|
||||||
@@ -1170,7 +1170,7 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
bool publishClimateHeating(UnitSystem unit = UnitSystem::METRIC, byte minTemp = 20, byte maxTemp = 90, bool enabledByDefault = true) {
|
bool publishClimateHeating(UnitSystem unit = UnitSystem::METRIC, uint8_t minTemp = 20, uint8_t maxTemp = 90, bool enabledByDefault = true) {
|
||||||
JsonDocument doc;
|
JsonDocument doc;
|
||||||
doc[FPSTR(HA_AVAILABILITY)][FPSTR(HA_TOPIC)] = this->statusTopic.c_str();
|
doc[FPSTR(HA_AVAILABILITY)][FPSTR(HA_TOPIC)] = this->statusTopic.c_str();
|
||||||
doc[FPSTR(HA_ENABLED_BY_DEFAULT)] = enabledByDefault;
|
doc[FPSTR(HA_ENABLED_BY_DEFAULT)] = enabledByDefault;
|
||||||
@@ -1222,7 +1222,7 @@ public:
|
|||||||
return this->publish(this->makeConfigTopic(FPSTR(HA_ENTITY_CLIMATE), F("heating"), '_').c_str(), doc);
|
return this->publish(this->makeConfigTopic(FPSTR(HA_ENTITY_CLIMATE), F("heating"), '_').c_str(), doc);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool publishClimateDhw(UnitSystem unit = UnitSystem::METRIC, byte minTemp = 40, byte maxTemp = 60, bool enabledByDefault = true) {
|
bool publishClimateDhw(UnitSystem unit = UnitSystem::METRIC, uint8_t minTemp = 40, uint8_t maxTemp = 60, bool enabledByDefault = true) {
|
||||||
JsonDocument doc;
|
JsonDocument doc;
|
||||||
doc[FPSTR(HA_AVAILABILITY)][FPSTR(HA_TOPIC)] = this->statusTopic.c_str();
|
doc[FPSTR(HA_AVAILABILITY)][FPSTR(HA_TOPIC)] = this->statusTopic.c_str();
|
||||||
doc[FPSTR(HA_ENABLED_BY_DEFAULT)] = enabledByDefault;
|
doc[FPSTR(HA_ENABLED_BY_DEFAULT)] = enabledByDefault;
|
||||||
|
|||||||
@@ -29,6 +29,7 @@ protected:
|
|||||||
enum class PumpStartReason {NONE, HEATING, ANTISTUCK};
|
enum class PumpStartReason {NONE, HEATING, ANTISTUCK};
|
||||||
|
|
||||||
Blinker* blinker = nullptr;
|
Blinker* blinker = nullptr;
|
||||||
|
unsigned long miscRunned = 0;
|
||||||
unsigned long lastHeapInfo = 0;
|
unsigned long lastHeapInfo = 0;
|
||||||
unsigned int minFreeHeap = 0;
|
unsigned int minFreeHeap = 0;
|
||||||
unsigned int minMaxFreeBlockHeap = 0;
|
unsigned int minMaxFreeBlockHeap = 0;
|
||||||
@@ -42,6 +43,8 @@ protected:
|
|||||||
bool telnetStarted = false;
|
bool telnetStarted = false;
|
||||||
bool emergencyDetected = false;
|
bool emergencyDetected = false;
|
||||||
unsigned long emergencyFlipTime = 0;
|
unsigned long emergencyFlipTime = 0;
|
||||||
|
bool freezeDetected = false;
|
||||||
|
unsigned long freezeDetectedTime = 0;
|
||||||
|
|
||||||
#if defined(ARDUINO_ARCH_ESP32)
|
#if defined(ARDUINO_ARCH_ESP32)
|
||||||
const char* getTaskName() override {
|
const char* getTaskName() override {
|
||||||
@@ -150,17 +153,16 @@ protected:
|
|||||||
|
|
||||||
Sensors::setConnectionStatusByType(Sensors::Type::MANUAL, false, false);
|
Sensors::setConnectionStatusByType(Sensors::Type::MANUAL, false, false);
|
||||||
}
|
}
|
||||||
this->yield();
|
|
||||||
|
|
||||||
this->emergency();
|
this->yield();
|
||||||
|
if (this->misc()) {
|
||||||
|
this->yield();
|
||||||
|
}
|
||||||
this->ledStatus();
|
this->ledStatus();
|
||||||
this->cascadeControl();
|
|
||||||
this->externalPump();
|
|
||||||
this->yield();
|
|
||||||
|
|
||||||
|
|
||||||
// telnet
|
// telnet
|
||||||
if (this->telnetStarted) {
|
if (this->telnetStarted) {
|
||||||
|
this->yield();
|
||||||
telnetStream->loop();
|
telnetStream->loop();
|
||||||
this->yield();
|
this->yield();
|
||||||
}
|
}
|
||||||
@@ -179,14 +181,27 @@ protected:
|
|||||||
|
|
||||||
// heap info
|
// heap info
|
||||||
this->heap();
|
this->heap();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool misc() {
|
||||||
|
if (millis() - this->miscRunned < 1000) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
// restart
|
// restart if required
|
||||||
if (this->restartSignalReceived && millis() - this->restartSignalReceivedTime > 15000) {
|
if (this->restartSignalReceived && millis() - this->restartSignalReceivedTime > 15000) {
|
||||||
this->restartSignalReceived = false;
|
this->restartSignalReceived = false;
|
||||||
|
|
||||||
ESP.restart();
|
ESP.restart();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
this->heating();
|
||||||
|
this->emergency();
|
||||||
|
this->cascadeControl();
|
||||||
|
this->externalPump();
|
||||||
|
this->miscRunned = millis();
|
||||||
|
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void heap() {
|
void heap() {
|
||||||
@@ -196,6 +211,7 @@ protected:
|
|||||||
// critical heap
|
// critical heap
|
||||||
if (!vars.states.restarting && (freeHeap < 2048 || maxFreeBlockHeap < 2048)) {
|
if (!vars.states.restarting && (freeHeap < 2048 || maxFreeBlockHeap < 2048)) {
|
||||||
this->restartSignalReceivedTime = millis();
|
this->restartSignalReceivedTime = millis();
|
||||||
|
this->restartSignalReceived = true;
|
||||||
vars.states.restarting = true;
|
vars.states.restarting = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -227,6 +243,65 @@ protected:
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void heating() {
|
||||||
|
// freeze protection
|
||||||
|
if (!settings.heating.enabled) {
|
||||||
|
float lowTemp = 255.0f;
|
||||||
|
uint8_t availableSensors = 0;
|
||||||
|
|
||||||
|
if (Sensors::existsConnectedSensorsByPurpose(Sensors::Purpose::INDOOR_TEMP)) {
|
||||||
|
auto value = Sensors::getMeanValueByPurpose(Sensors::Purpose::INDOOR_TEMP, Sensors::ValueType::PRIMARY);
|
||||||
|
if (value < lowTemp) {
|
||||||
|
lowTemp = value;
|
||||||
|
}
|
||||||
|
|
||||||
|
availableSensors++;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (Sensors::existsConnectedSensorsByPurpose(Sensors::Purpose::HEATING_TEMP)) {
|
||||||
|
auto value = Sensors::getMeanValueByPurpose(Sensors::Purpose::HEATING_TEMP, Sensors::ValueType::PRIMARY);
|
||||||
|
if (value < lowTemp) {
|
||||||
|
lowTemp = value;
|
||||||
|
}
|
||||||
|
|
||||||
|
availableSensors++;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (Sensors::existsConnectedSensorsByPurpose(Sensors::Purpose::HEATING_RETURN_TEMP)) {
|
||||||
|
auto value = Sensors::getMeanValueByPurpose(Sensors::Purpose::HEATING_RETURN_TEMP, Sensors::ValueType::PRIMARY);
|
||||||
|
if (value < lowTemp) {
|
||||||
|
lowTemp = value;
|
||||||
|
}
|
||||||
|
|
||||||
|
availableSensors++;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (availableSensors && lowTemp <= settings.heating.freezeProtection.lowTemp) {
|
||||||
|
if (!this->freezeDetected) {
|
||||||
|
this->freezeDetected = true;
|
||||||
|
this->freezeDetectedTime = millis();
|
||||||
|
|
||||||
|
} else if (millis() - this->freezeDetectedTime > (settings.heating.freezeProtection.thresholdTime * 1000)) {
|
||||||
|
this->freezeDetected = false;
|
||||||
|
settings.heating.enabled = true;
|
||||||
|
fsSettings.update();
|
||||||
|
|
||||||
|
Log.sinfoln(
|
||||||
|
FPSTR(L_MAIN),
|
||||||
|
F("Heating turned on by freeze protection, current low temp: %.2f, threshold: %hhu"),
|
||||||
|
lowTemp, settings.heating.freezeProtection.lowTemp
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
} else if (this->freezeDetected) {
|
||||||
|
this->freezeDetected = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
} else if (this->freezeDetected) {
|
||||||
|
this->freezeDetected = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void emergency() {
|
void emergency() {
|
||||||
// flags
|
// flags
|
||||||
uint8_t emergencyFlags = 0b00000000;
|
uint8_t emergencyFlags = 0b00000000;
|
||||||
|
|||||||
@@ -557,7 +557,7 @@ protected:
|
|||||||
}
|
}
|
||||||
|
|
||||||
bool publishNonStaticHaEntities(bool force = false) {
|
bool publishNonStaticHaEntities(bool force = false) {
|
||||||
static byte _heatingMinTemp, _heatingMaxTemp, _dhwMinTemp, _dhwMaxTemp = 0;
|
static uint8_t _heatingMinTemp, _heatingMaxTemp, _dhwMinTemp, _dhwMaxTemp = 0;
|
||||||
static bool _indoorTempControl, _dhwSupport = false;
|
static bool _indoorTempControl, _dhwSupport = false;
|
||||||
|
|
||||||
bool published = false;
|
bool published = false;
|
||||||
|
|||||||
@@ -19,8 +19,8 @@ protected:
|
|||||||
|
|
||||||
CustomOpenTherm* instance = nullptr;
|
CustomOpenTherm* instance = nullptr;
|
||||||
unsigned long instanceCreatedTime = 0;
|
unsigned long instanceCreatedTime = 0;
|
||||||
byte instanceInGpio = 0;
|
uint8_t instanceInGpio = 0;
|
||||||
byte instanceOutGpio = 0;
|
uint8_t instanceOutGpio = 0;
|
||||||
bool initialized = false;
|
bool initialized = false;
|
||||||
unsigned long connectedTime = 0;
|
unsigned long connectedTime = 0;
|
||||||
unsigned long disconnectedTime = 0;
|
unsigned long disconnectedTime = 0;
|
||||||
@@ -31,7 +31,7 @@ protected:
|
|||||||
unsigned long heatingSetTempTime = 0;
|
unsigned long heatingSetTempTime = 0;
|
||||||
unsigned long dhwSetTempTime = 0;
|
unsigned long dhwSetTempTime = 0;
|
||||||
unsigned long ch2SetTempTime = 0;
|
unsigned long ch2SetTempTime = 0;
|
||||||
byte configuredRxLedGpio = GPIO_IS_NOT_CONFIGURED;
|
uint8_t configuredRxLedGpio = GPIO_IS_NOT_CONFIGURED;
|
||||||
|
|
||||||
#if defined(ARDUINO_ARCH_ESP32)
|
#if defined(ARDUINO_ARCH_ESP32)
|
||||||
const char* getTaskName() override {
|
const char* getTaskName() override {
|
||||||
@@ -90,11 +90,16 @@ protected:
|
|||||||
|
|
||||||
Log.sinfoln(FPSTR(L_OT), F("Started. GPIO IN: %hhu, GPIO OUT: %hhu"), settings.opentherm.inGpio, settings.opentherm.outGpio);
|
Log.sinfoln(FPSTR(L_OT), F("Started. GPIO IN: %hhu, GPIO OUT: %hhu"), settings.opentherm.inGpio, settings.opentherm.outGpio);
|
||||||
|
|
||||||
this->instance->setAfterSendRequestCallback([this](unsigned long request, unsigned long response, OpenThermResponseStatus status, byte attempt) {
|
this->instance->setAfterSendRequestCallback([this](unsigned long request, unsigned long response, OpenThermResponseStatus status, uint8_t attempt) {
|
||||||
Log.sverboseln(
|
Log.sverboseln(
|
||||||
FPSTR(L_OT),
|
FPSTR(L_OT),
|
||||||
F("ID: %4d Request: %8lx Response: %8lx Attempt: %2d Status: %s"),
|
F("ID: %4d Request: %8lx Response: %8lx Msg type: %s Attempt: %2d Status: %s"),
|
||||||
CustomOpenTherm::getDataID(request), request, response, attempt, CustomOpenTherm::statusToString(status)
|
CustomOpenTherm::getDataID(request),
|
||||||
|
request,
|
||||||
|
response,
|
||||||
|
CustomOpenTherm::getResponseMessageTypeString(response),
|
||||||
|
attempt,
|
||||||
|
CustomOpenTherm::statusToString(status)
|
||||||
);
|
);
|
||||||
|
|
||||||
if (status == OpenThermResponseStatus::SUCCESS) {
|
if (status == OpenThermResponseStatus::SUCCESS) {
|
||||||
@@ -138,7 +143,12 @@ protected:
|
|||||||
return;
|
return;
|
||||||
|
|
||||||
} else if (this->instance->status == OpenThermStatus::NOT_INITIALIZED) {
|
} else if (this->instance->status == OpenThermStatus::NOT_INITIALIZED) {
|
||||||
this->instance->begin();
|
if (!this->instance->begin()) {
|
||||||
|
Log.swarningln(FPSTR(L_OT), F("Failed begin"));
|
||||||
|
|
||||||
|
this->delay(5000);
|
||||||
|
return;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// RX LED GPIO setup
|
// RX LED GPIO setup
|
||||||
@@ -159,12 +169,15 @@ protected:
|
|||||||
|
|
||||||
// Heating settings
|
// Heating settings
|
||||||
vars.master.heating.enabled = this->isReady()
|
vars.master.heating.enabled = this->isReady()
|
||||||
&& (settings.heating.enabled || vars.emergency.state)
|
&& settings.heating.enabled
|
||||||
&& vars.cascadeControl.input
|
&& vars.cascadeControl.input
|
||||||
&& !vars.master.heating.blocking;
|
&& !vars.master.heating.blocking
|
||||||
|
&& !vars.master.heating.overheat;
|
||||||
|
|
||||||
// DHW settings
|
// DHW settings
|
||||||
vars.master.dhw.enabled = settings.opentherm.options.dhwSupport && settings.dhw.enabled;
|
vars.master.dhw.enabled = settings.opentherm.options.dhwSupport
|
||||||
|
&& settings.dhw.enabled
|
||||||
|
&& !vars.master.dhw.overheat;
|
||||||
vars.master.dhw.targetTemp = settings.dhw.target;
|
vars.master.dhw.targetTemp = settings.dhw.target;
|
||||||
|
|
||||||
// CH2 settings
|
// CH2 settings
|
||||||
@@ -195,6 +208,12 @@ protected:
|
|||||||
summerWinterMode = vars.master.heating.enabled == summerWinterMode;
|
summerWinterMode = vars.master.heating.enabled == summerWinterMode;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// DHW blocking
|
||||||
|
bool dhwBlocking = settings.opentherm.options.dhwBlocking;
|
||||||
|
if (settings.opentherm.options.dhwStateAsDhwBlocking) {
|
||||||
|
dhwBlocking = vars.master.dhw.enabled == dhwBlocking;
|
||||||
|
}
|
||||||
|
|
||||||
unsigned long response = this->instance->setBoilerStatus(
|
unsigned long response = this->instance->setBoilerStatus(
|
||||||
vars.master.heating.enabled,
|
vars.master.heating.enabled,
|
||||||
vars.master.dhw.enabled,
|
vars.master.dhw.enabled,
|
||||||
@@ -202,7 +221,7 @@ protected:
|
|||||||
settings.opentherm.options.nativeHeatingControl,
|
settings.opentherm.options.nativeHeatingControl,
|
||||||
vars.master.ch2.enabled,
|
vars.master.ch2.enabled,
|
||||||
summerWinterMode,
|
summerWinterMode,
|
||||||
settings.opentherm.options.dhwBlocking,
|
dhwBlocking,
|
||||||
statusLb
|
statusLb
|
||||||
);
|
);
|
||||||
|
|
||||||
@@ -212,6 +231,27 @@ protected:
|
|||||||
F("Failed receive boiler status: %s"),
|
F("Failed receive boiler status: %s"),
|
||||||
CustomOpenTherm::statusToString(this->instance->getLastResponseStatus())
|
CustomOpenTherm::statusToString(this->instance->getLastResponseStatus())
|
||||||
);
|
);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
vars.slave.heating.active = CustomOpenTherm::isCentralHeatingActive(response);
|
||||||
|
vars.slave.dhw.active = settings.opentherm.options.dhwSupport ? CustomOpenTherm::isHotWaterActive(response) : false;
|
||||||
|
vars.slave.flame = CustomOpenTherm::isFlameOn(response);
|
||||||
|
vars.slave.cooling = CustomOpenTherm::isCoolingActive(response);
|
||||||
|
vars.slave.ch2.active = CustomOpenTherm::isCh2Active(response);
|
||||||
|
vars.slave.fault.active = CustomOpenTherm::isFault(response);
|
||||||
|
|
||||||
|
if (!settings.opentherm.options.ignoreDiagState) {
|
||||||
|
vars.slave.diag.active = CustomOpenTherm::isDiagnostic(response);
|
||||||
|
|
||||||
|
} else if (vars.slave.diag.active) {
|
||||||
|
vars.slave.diag.active = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
Log.snoticeln(
|
||||||
|
FPSTR(L_OT), F("Received boiler status. Heating: %hhu; DHW: %hhu; flame: %hhu; cooling: %hhu; channel 2: %hhu; fault: %hhu; diag: %hhu"),
|
||||||
|
vars.slave.heating.active, vars.slave.dhw.active,
|
||||||
|
vars.slave.flame, vars.slave.cooling, vars.slave.ch2.active, vars.slave.fault.active, vars.slave.diag.active
|
||||||
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
// 5 request retries
|
// 5 request retries
|
||||||
@@ -257,6 +297,15 @@ protected:
|
|||||||
Sensors::setConnectionStatusByType(Sensors::Type::OT_FAN_SPEED_SETPOINT, false);
|
Sensors::setConnectionStatusByType(Sensors::Type::OT_FAN_SPEED_SETPOINT, false);
|
||||||
Sensors::setConnectionStatusByType(Sensors::Type::OT_FAN_SPEED_CURRENT, false);
|
Sensors::setConnectionStatusByType(Sensors::Type::OT_FAN_SPEED_CURRENT, false);
|
||||||
|
|
||||||
|
Sensors::setConnectionStatusByType(Sensors::Type::OT_BURNER_STARTS, false);
|
||||||
|
Sensors::setConnectionStatusByType(Sensors::Type::OT_DHW_BURNER_STARTS, false);
|
||||||
|
Sensors::setConnectionStatusByType(Sensors::Type::OT_HEATING_PUMP_STARTS, false);
|
||||||
|
Sensors::setConnectionStatusByType(Sensors::Type::OT_DHW_PUMP_STARTS, false);
|
||||||
|
Sensors::setConnectionStatusByType(Sensors::Type::OT_BURNER_HOURS, false);
|
||||||
|
Sensors::setConnectionStatusByType(Sensors::Type::OT_DHW_BURNER_HOURS, false);
|
||||||
|
Sensors::setConnectionStatusByType(Sensors::Type::OT_HEATING_PUMP_HOURS, false);
|
||||||
|
Sensors::setConnectionStatusByType(Sensors::Type::OT_DHW_PUMP_HOURS, false);
|
||||||
|
|
||||||
this->initialized = false;
|
this->initialized = false;
|
||||||
this->disconnectedTime = millis();
|
this->disconnectedTime = millis();
|
||||||
vars.slave.connected = false;
|
vars.slave.connected = false;
|
||||||
@@ -310,34 +359,60 @@ protected:
|
|||||||
Log.sinfoln(FPSTR(L_OT_DHW), vars.master.dhw.enabled ? F("Enabled") : F("Disabled"));
|
Log.sinfoln(FPSTR(L_OT_DHW), vars.master.dhw.enabled ? F("Enabled") : F("Disabled"));
|
||||||
}
|
}
|
||||||
|
|
||||||
vars.slave.heating.active = CustomOpenTherm::isCentralHeatingActive(response);
|
|
||||||
vars.slave.dhw.active = settings.opentherm.options.dhwSupport ? CustomOpenTherm::isHotWaterActive(response) : false;
|
|
||||||
vars.slave.flame = CustomOpenTherm::isFlameOn(response);
|
|
||||||
vars.slave.cooling = CustomOpenTherm::isCoolingActive(response);
|
|
||||||
vars.slave.fault.active = CustomOpenTherm::isFault(response);
|
|
||||||
vars.slave.diag.active = CustomOpenTherm::isDiagnostic(response);
|
|
||||||
|
|
||||||
Log.snoticeln(
|
|
||||||
FPSTR(L_OT), F("Received boiler status. Heating: %hhu; DHW: %hhu; flame: %hhu; cooling: %hhu; fault: %hhu; diag: %hhu"),
|
|
||||||
vars.slave.heating.active, vars.slave.dhw.active,
|
|
||||||
vars.slave.flame, vars.slave.cooling, vars.slave.fault.active, vars.slave.diag.active
|
|
||||||
);
|
|
||||||
|
|
||||||
// These parameters will be updated every minute
|
// These parameters will be updated every minute
|
||||||
if (millis() - this->prevUpdateNonEssentialVars > 60000) {
|
if (millis() - this->prevUpdateNonEssentialVars > 60000) {
|
||||||
|
// Set date & time
|
||||||
|
if (settings.opentherm.options.setDateAndTime) {
|
||||||
|
struct tm ti;
|
||||||
|
|
||||||
|
if (getLocalTime(&ti)) {
|
||||||
|
if (this->setYear(&ti)) {
|
||||||
|
Log.sinfoln(FPSTR(L_OT), F("Year of date set successfully"));
|
||||||
|
|
||||||
|
} else {
|
||||||
|
Log.sinfoln(FPSTR(L_OT), F("Failed set year of date"));
|
||||||
|
}
|
||||||
|
|
||||||
|
if (this->setDayAndMonth(&ti)) {
|
||||||
|
Log.sinfoln(FPSTR(L_OT), F("Day and month of date set successfully"));
|
||||||
|
|
||||||
|
} else {
|
||||||
|
Log.sinfoln(FPSTR(L_OT), F("Failed set day and month of date"));
|
||||||
|
}
|
||||||
|
|
||||||
|
if (this->setTime(&ti)) {
|
||||||
|
Log.sinfoln(FPSTR(L_OT), F("Time set successfully"));
|
||||||
|
|
||||||
|
} else {
|
||||||
|
Log.sinfoln(FPSTR(L_OT), F("Failed set time"));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Get min modulation level & max power
|
||||||
if (this->updateMinModulationLevel()) {
|
if (this->updateMinModulationLevel()) {
|
||||||
Log.snoticeln(
|
Log.snoticeln(
|
||||||
FPSTR(L_OT), F("Received min modulation: %hhu%%, max power: %.2f kW"),
|
FPSTR(L_OT), F("Received min modulation: %hhu%%, max power: %.2f kW"),
|
||||||
vars.slave.modulation.min, vars.slave.power.max
|
vars.slave.modulation.min, vars.slave.power.max
|
||||||
);
|
);
|
||||||
|
|
||||||
if (settings.opentherm.maxModulation < vars.slave.modulation.min) {
|
if (settings.heating.maxModulation < vars.slave.modulation.min) {
|
||||||
settings.opentherm.maxModulation = vars.slave.modulation.min;
|
settings.heating.maxModulation = vars.slave.modulation.min;
|
||||||
fsSettings.update();
|
fsSettings.update();
|
||||||
|
|
||||||
Log.swarningln(
|
Log.swarningln(
|
||||||
FPSTR(L_SETTINGS_OT), F("Updated min modulation: %hhu%%"),
|
FPSTR(L_SETTINGS_HEATING), F("Updated min modulation: %hhu%%"),
|
||||||
settings.opentherm.maxModulation
|
settings.heating.maxModulation
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (settings.dhw.maxModulation < vars.slave.modulation.min) {
|
||||||
|
settings.dhw.maxModulation = vars.slave.modulation.min;
|
||||||
|
fsSettings.update();
|
||||||
|
|
||||||
|
Log.swarningln(
|
||||||
|
FPSTR(L_SETTINGS_DHW), F("Updated min modulation: %hhu%%"),
|
||||||
|
settings.dhw.maxModulation
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -356,29 +431,6 @@ protected:
|
|||||||
Log.swarningln(FPSTR(L_OT), F("Failed receive min modulation and max power"));
|
Log.swarningln(FPSTR(L_OT), F("Failed receive min modulation and max power"));
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!vars.master.heating.enabled && settings.opentherm.options.modulationSyncWithHeating) {
|
|
||||||
if (this->setMaxModulationLevel(0)) {
|
|
||||||
Log.snoticeln(FPSTR(L_OT), F("Set max modulation: 0% (response: %hhu%%)"), vars.slave.modulation.max);
|
|
||||||
|
|
||||||
} else {
|
|
||||||
Log.swarningln(FPSTR(L_OT), F("Failed set max modulation: 0% (response: %hhu%%)"), vars.slave.modulation.max);
|
|
||||||
}
|
|
||||||
|
|
||||||
} else {
|
|
||||||
if (this->setMaxModulationLevel(settings.opentherm.maxModulation)) {
|
|
||||||
Log.snoticeln(
|
|
||||||
FPSTR(L_OT), F("Set max modulation: %hhu%% (response: %hhu%%)"),
|
|
||||||
settings.opentherm.maxModulation, vars.slave.modulation.max
|
|
||||||
);
|
|
||||||
|
|
||||||
} else {
|
|
||||||
Log.swarningln(
|
|
||||||
FPSTR(L_OT), F("Failed set max modulation: %hhu%% (response: %hhu%%)"),
|
|
||||||
settings.opentherm.maxModulation, vars.slave.modulation.max
|
|
||||||
);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
// Get DHW min/max temp (if necessary)
|
// Get DHW min/max temp (if necessary)
|
||||||
if (settings.opentherm.options.dhwSupport && settings.opentherm.options.getMinMaxTemp) {
|
if (settings.opentherm.options.dhwSupport && settings.opentherm.options.getMinMaxTemp) {
|
||||||
@@ -503,9 +555,160 @@ protected:
|
|||||||
vars.slave.diag.code = 0;
|
vars.slave.diag.code = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Update burner starts
|
||||||
|
if (Sensors::getAmountByType(Sensors::Type::OT_BURNER_STARTS, true)) {
|
||||||
|
if (this->updateBurnerStarts()) {
|
||||||
|
Log.snoticeln(FPSTR(L_OT), F("Received burner starts: %hu"), vars.slave.stats.burnerStarts);
|
||||||
|
|
||||||
|
Sensors::setValueByType(
|
||||||
|
Sensors::Type::OT_BURNER_STARTS, vars.slave.stats.burnerStarts,
|
||||||
|
Sensors::ValueType::PRIMARY, true, true
|
||||||
|
);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
Log.swarningln(FPSTR(L_OT), F("Failed receive burner starts"));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Update DHW burner starts
|
||||||
|
if (Sensors::getAmountByType(Sensors::Type::OT_DHW_BURNER_STARTS, true)) {
|
||||||
|
if (this->updateDhwBurnerStarts()) {
|
||||||
|
Log.snoticeln(FPSTR(L_OT), F("Received DHW burner starts: %hu"), vars.slave.stats.dhwBurnerStarts);
|
||||||
|
|
||||||
|
Sensors::setValueByType(
|
||||||
|
Sensors::Type::OT_DHW_BURNER_STARTS, vars.slave.stats.dhwBurnerStarts,
|
||||||
|
Sensors::ValueType::PRIMARY, true, true
|
||||||
|
);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
Log.swarningln(FPSTR(L_OT), F("Failed receive DHW burner starts"));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Update heating pump starts
|
||||||
|
if (Sensors::getAmountByType(Sensors::Type::OT_HEATING_PUMP_STARTS, true)) {
|
||||||
|
if (this->updateHeatingPumpStarts()) {
|
||||||
|
Log.snoticeln(FPSTR(L_OT), F("Received heating pump starts: %hu"), vars.slave.stats.heatingPumpStarts);
|
||||||
|
|
||||||
|
Sensors::setValueByType(
|
||||||
|
Sensors::Type::OT_HEATING_PUMP_STARTS, vars.slave.stats.heatingPumpStarts,
|
||||||
|
Sensors::ValueType::PRIMARY, true, true
|
||||||
|
);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
Log.swarningln(FPSTR(L_OT), F("Failed receive heating pump starts"));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Update DHW pump starts
|
||||||
|
if (Sensors::getAmountByType(Sensors::Type::OT_DHW_PUMP_STARTS, true)) {
|
||||||
|
if (this->updateDhwPumpStarts()) {
|
||||||
|
Log.snoticeln(FPSTR(L_OT), F("Received DHW pump starts: %hu"), vars.slave.stats.dhwPumpStarts);
|
||||||
|
|
||||||
|
Sensors::setValueByType(
|
||||||
|
Sensors::Type::OT_DHW_PUMP_STARTS, vars.slave.stats.dhwPumpStarts,
|
||||||
|
Sensors::ValueType::PRIMARY, true, true
|
||||||
|
);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
Log.swarningln(FPSTR(L_OT), F("Failed receive DHW pump starts"));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Update burner hours
|
||||||
|
if (Sensors::getAmountByType(Sensors::Type::OT_BURNER_HOURS, true)) {
|
||||||
|
if (this->updateBurnerHours()) {
|
||||||
|
Log.snoticeln(FPSTR(L_OT), F("Received burner hours: %hu"), vars.slave.stats.burnerHours);
|
||||||
|
|
||||||
|
Sensors::setValueByType(
|
||||||
|
Sensors::Type::OT_BURNER_HOURS, vars.slave.stats.burnerHours,
|
||||||
|
Sensors::ValueType::PRIMARY, true, true
|
||||||
|
);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
Log.swarningln(FPSTR(L_OT), F("Failed receive burner hours"));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Update DHW burner hours
|
||||||
|
if (Sensors::getAmountByType(Sensors::Type::OT_DHW_BURNER_HOURS, true)) {
|
||||||
|
if (this->updateDhwBurnerHours()) {
|
||||||
|
Log.snoticeln(FPSTR(L_OT), F("Received DHW burner hours: %hu"), vars.slave.stats.dhwBurnerHours);
|
||||||
|
|
||||||
|
Sensors::setValueByType(
|
||||||
|
Sensors::Type::OT_DHW_BURNER_HOURS, vars.slave.stats.dhwBurnerHours,
|
||||||
|
Sensors::ValueType::PRIMARY, true, true
|
||||||
|
);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
Log.swarningln(FPSTR(L_OT), F("Failed receive DHW burner hours"));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Update heating pump hours
|
||||||
|
if (Sensors::getAmountByType(Sensors::Type::OT_HEATING_PUMP_HOURS, true)) {
|
||||||
|
if (this->updateHeatingPumpHours()) {
|
||||||
|
Log.snoticeln(FPSTR(L_OT), F("Received heating pump hours: %hu"), vars.slave.stats.heatingPumpHours);
|
||||||
|
|
||||||
|
Sensors::setValueByType(
|
||||||
|
Sensors::Type::OT_HEATING_PUMP_HOURS, vars.slave.stats.heatingPumpHours,
|
||||||
|
Sensors::ValueType::PRIMARY, true, true
|
||||||
|
);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
Log.swarningln(FPSTR(L_OT), F("Failed receive heating pump hours"));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Update DHW pump hours
|
||||||
|
if (Sensors::getAmountByType(Sensors::Type::OT_DHW_PUMP_HOURS, true)) {
|
||||||
|
if (this->updateDhwPumpHours()) {
|
||||||
|
Log.snoticeln(FPSTR(L_OT), F("Received DHW pump hours: %hu"), vars.slave.stats.dhwPumpHours);
|
||||||
|
|
||||||
|
Sensors::setValueByType(
|
||||||
|
Sensors::Type::OT_DHW_PUMP_HOURS, vars.slave.stats.dhwPumpHours,
|
||||||
|
Sensors::ValueType::PRIMARY, true, true
|
||||||
|
);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
Log.swarningln(FPSTR(L_OT), F("Failed receive DHW pump hours"));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Auto fault reset
|
||||||
|
if (settings.opentherm.options.autoFaultReset && vars.slave.fault.active && !vars.actions.resetFault) {
|
||||||
|
vars.actions.resetFault = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Auto diag reset
|
||||||
|
if (settings.opentherm.options.autoDiagReset && vars.slave.diag.active && !vars.actions.resetDiagnostic) {
|
||||||
|
vars.actions.resetDiagnostic = true;
|
||||||
|
}
|
||||||
|
|
||||||
this->prevUpdateNonEssentialVars = millis();
|
this->prevUpdateNonEssentialVars = millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Set max modulation level
|
||||||
|
uint8_t targetMaxModulation = vars.slave.modulation.max;
|
||||||
|
if (vars.slave.heating.active) {
|
||||||
|
targetMaxModulation = settings.heating.maxModulation;
|
||||||
|
|
||||||
|
} else if (vars.slave.dhw.active) {
|
||||||
|
targetMaxModulation = settings.dhw.maxModulation;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (this->setMaxModulationLevel(targetMaxModulation)) {
|
||||||
|
Log.snoticeln(
|
||||||
|
FPSTR(L_OT), F("Set max modulation: %hhu%% (response: %hhu%%)"),
|
||||||
|
targetMaxModulation, vars.slave.modulation.max
|
||||||
|
);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
Log.swarningln(
|
||||||
|
FPSTR(L_OT), F("Failed set max modulation: %hhu%% (response: %hhu%%)"),
|
||||||
|
targetMaxModulation, vars.slave.modulation.max
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
// Update modulation level
|
// Update modulation level
|
||||||
if (
|
if (
|
||||||
@@ -1114,6 +1317,84 @@ protected:
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Heating overheat control
|
||||||
|
if (settings.heating.overheatProtection.highTemp > 0 && settings.heating.overheatProtection.lowTemp > 0) {
|
||||||
|
float highTemp = convertTemp(
|
||||||
|
max({
|
||||||
|
vars.slave.heating.currentTemp,
|
||||||
|
vars.slave.heating.returnTemp,
|
||||||
|
vars.slave.heatExchangerTemp
|
||||||
|
}),
|
||||||
|
settings.opentherm.unitSystem,
|
||||||
|
settings.system.unitSystem
|
||||||
|
);
|
||||||
|
|
||||||
|
if (vars.master.heating.overheat) {
|
||||||
|
if ((float) settings.heating.overheatProtection.lowTemp - highTemp + 0.0001f >= 0.0f) {
|
||||||
|
vars.master.heating.overheat = false;
|
||||||
|
|
||||||
|
Log.sinfoln(
|
||||||
|
FPSTR(L_OT_HEATING), F("Overheating not detected. Current high temp: %.2f, threshold (low): %hhu"),
|
||||||
|
highTemp, settings.heating.overheatProtection.lowTemp
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
} else if (vars.slave.heating.active) {
|
||||||
|
if (highTemp - (float) settings.heating.overheatProtection.highTemp + 0.0001f >= 0.0f) {
|
||||||
|
vars.master.heating.overheat = true;
|
||||||
|
|
||||||
|
Log.swarningln(
|
||||||
|
FPSTR(L_OT_HEATING), F("Overheating detected! Current high temp: %.2f, threshold (high): %hhu"),
|
||||||
|
highTemp, settings.heating.overheatProtection.highTemp
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
} else if (vars.master.heating.overheat) {
|
||||||
|
vars.master.heating.overheat = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// DHW overheat control
|
||||||
|
if (settings.dhw.overheatProtection.highTemp > 0 && settings.dhw.overheatProtection.lowTemp > 0) {
|
||||||
|
float highTemp = convertTemp(
|
||||||
|
max({
|
||||||
|
vars.slave.heating.currentTemp,
|
||||||
|
vars.slave.heating.returnTemp,
|
||||||
|
vars.slave.heatExchangerTemp,
|
||||||
|
vars.slave.dhw.currentTemp,
|
||||||
|
vars.slave.dhw.currentTemp2,
|
||||||
|
vars.slave.dhw.returnTemp
|
||||||
|
}),
|
||||||
|
settings.opentherm.unitSystem,
|
||||||
|
settings.system.unitSystem
|
||||||
|
);
|
||||||
|
|
||||||
|
if (vars.master.dhw.overheat) {
|
||||||
|
if ((float) settings.dhw.overheatProtection.lowTemp - highTemp + 0.0001f >= 0.0f) {
|
||||||
|
vars.master.dhw.overheat = false;
|
||||||
|
|
||||||
|
Log.sinfoln(
|
||||||
|
FPSTR(L_OT_DHW), F("Overheating not detected. Current high temp: %.2f, threshold (low): %hhu"),
|
||||||
|
highTemp, settings.dhw.overheatProtection.lowTemp
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
} else if (vars.slave.dhw.active) {
|
||||||
|
if (highTemp - (float) settings.dhw.overheatProtection.highTemp + 0.0001f >= 0.0f) {
|
||||||
|
vars.master.dhw.overheat = true;
|
||||||
|
|
||||||
|
Log.swarningln(
|
||||||
|
FPSTR(L_OT_DHW), F("Overheating detected! Current high temp: %.2f, threshold (high): %hhu"),
|
||||||
|
highTemp, settings.dhw.overheatProtection.highTemp
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
} else if (vars.master.dhw.overheat) {
|
||||||
|
vars.master.dhw.overheat = false;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void initialize() {
|
void initialize() {
|
||||||
@@ -1179,17 +1460,17 @@ protected:
|
|||||||
|
|
||||||
bool needSetDhwTemp(const float target) {
|
bool needSetDhwTemp(const float target) {
|
||||||
return millis() - this->dhwSetTempTime > this->dhwSetTempInterval
|
return millis() - this->dhwSetTempTime > this->dhwSetTempInterval
|
||||||
|| fabsf(target - vars.slave.dhw.targetTemp) > 0.001f;
|
|| fabsf(target - vars.slave.dhw.targetTemp) > 0.05f;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool needSetHeatingTemp(const float target) {
|
bool needSetHeatingTemp(const float target) {
|
||||||
return millis() - this->heatingSetTempTime > this->heatingSetTempInterval
|
return millis() - this->heatingSetTempTime > this->heatingSetTempInterval
|
||||||
|| fabsf(target - vars.slave.heating.targetTemp) > 0.001f;
|
|| fabsf(target - vars.slave.heating.targetTemp) > 0.05f;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool needSetCh2Temp(const float target) {
|
bool needSetCh2Temp(const float target) {
|
||||||
return millis() - this->ch2SetTempTime > this->ch2SetTempInterval
|
return millis() - this->ch2SetTempTime > this->ch2SetTempInterval
|
||||||
|| fabsf(target - vars.slave.ch2.targetTemp) > 0.001f;
|
|| fabsf(target - vars.slave.ch2.targetTemp) > 0.05f;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool updateSlaveConfig() {
|
bool updateSlaveConfig() {
|
||||||
@@ -1228,6 +1509,64 @@ protected:
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool setYear(const struct tm *ptm) {
|
||||||
|
const unsigned int request = (ptm->tm_year + 1900) & 0xFFFF;
|
||||||
|
const unsigned long response = this->instance->sendRequest(CustomOpenTherm::buildRequest(
|
||||||
|
OpenThermRequestType::WRITE_DATA,
|
||||||
|
OpenThermMessageID::Year,
|
||||||
|
request
|
||||||
|
));
|
||||||
|
|
||||||
|
if (!CustomOpenTherm::isValidResponse(response)) {
|
||||||
|
return false;
|
||||||
|
|
||||||
|
} else if (!CustomOpenTherm::isValidResponseId(response, OpenThermMessageID::Year)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
return CustomOpenTherm::getUInt(response) == request;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool setDayAndMonth(const struct tm *ptm) {
|
||||||
|
const uint8_t month = (ptm->tm_mon + 1) & 0xFF;
|
||||||
|
const unsigned int request = (month << 8) | (ptm->tm_mday & 0xFF);
|
||||||
|
const unsigned long response = this->instance->sendRequest(CustomOpenTherm::buildRequest(
|
||||||
|
OpenThermRequestType::WRITE_DATA,
|
||||||
|
OpenThermMessageID::Date,
|
||||||
|
request
|
||||||
|
));
|
||||||
|
|
||||||
|
if (!CustomOpenTherm::isValidResponse(response)) {
|
||||||
|
return false;
|
||||||
|
|
||||||
|
} else if (!CustomOpenTherm::isValidResponseId(response, OpenThermMessageID::Date)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
return CustomOpenTherm::getUInt(response) == request;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool setTime(const struct tm *ptm) {
|
||||||
|
const uint8_t dayOfWeek = ptm->tm_wday == 0 ? 6 : ptm->tm_wday - 1;
|
||||||
|
const unsigned int request = ((dayOfWeek & 0x07) << 13)
|
||||||
|
| ((ptm->tm_hour & 0x1F) << 8)
|
||||||
|
| (ptm->tm_min & 0x3F);
|
||||||
|
|
||||||
|
const unsigned long response = this->instance->sendRequest(CustomOpenTherm::buildRequest(
|
||||||
|
OpenThermRequestType::WRITE_DATA,
|
||||||
|
OpenThermMessageID::DayTime,
|
||||||
|
request
|
||||||
|
));
|
||||||
|
|
||||||
|
if (!CustomOpenTherm::isValidResponse(response)) {
|
||||||
|
return false;
|
||||||
|
|
||||||
|
} else if (!CustomOpenTherm::isValidResponseId(response, OpenThermMessageID::DayTime)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
return CustomOpenTherm::getUInt(response) == request;
|
||||||
|
}
|
||||||
|
|
||||||
bool setMaxModulationLevel(const uint8_t value) {
|
bool setMaxModulationLevel(const uint8_t value) {
|
||||||
const unsigned int request = CustomOpenTherm::toFloat(value);
|
const unsigned int request = CustomOpenTherm::toFloat(value);
|
||||||
@@ -1350,7 +1689,7 @@ protected:
|
|||||||
return CustomOpenTherm::getUInt(response) == request;
|
return CustomOpenTherm::getUInt(response) == request;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool setMaxHeatingTemp(const uint8_t temperature) {
|
bool setMaxHeatingTemp(const float temperature) {
|
||||||
const unsigned int request = CustomOpenTherm::temperatureToData(temperature);
|
const unsigned int request = CustomOpenTherm::temperatureToData(temperature);
|
||||||
const unsigned long response = this->instance->sendRequest(CustomOpenTherm::buildRequest(
|
const unsigned long response = this->instance->sendRequest(CustomOpenTherm::buildRequest(
|
||||||
OpenThermMessageType::WRITE_DATA,
|
OpenThermMessageType::WRITE_DATA,
|
||||||
@@ -1640,6 +1979,158 @@ protected:
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool updateBurnerStarts() {
|
||||||
|
const unsigned long response = this->instance->sendRequest(CustomOpenTherm::buildRequest(
|
||||||
|
OpenThermRequestType::READ_DATA,
|
||||||
|
OpenThermMessageID::SuccessfulBurnerStarts,
|
||||||
|
0
|
||||||
|
));
|
||||||
|
|
||||||
|
if (!CustomOpenTherm::isValidResponse(response)) {
|
||||||
|
return false;
|
||||||
|
|
||||||
|
} else if (!CustomOpenTherm::isValidResponseId(response, OpenThermMessageID::SuccessfulBurnerStarts)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
vars.slave.stats.burnerStarts = CustomOpenTherm::getUInt(response);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool updateDhwBurnerStarts() {
|
||||||
|
const unsigned long response = this->instance->sendRequest(CustomOpenTherm::buildRequest(
|
||||||
|
OpenThermRequestType::READ_DATA,
|
||||||
|
OpenThermMessageID::DHWBurnerStarts,
|
||||||
|
0
|
||||||
|
));
|
||||||
|
|
||||||
|
if (!CustomOpenTherm::isValidResponse(response)) {
|
||||||
|
return false;
|
||||||
|
|
||||||
|
} else if (!CustomOpenTherm::isValidResponseId(response, OpenThermMessageID::DHWBurnerStarts)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
vars.slave.stats.dhwBurnerStarts = CustomOpenTherm::getUInt(response);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool updateHeatingPumpStarts() {
|
||||||
|
const unsigned long response = this->instance->sendRequest(CustomOpenTherm::buildRequest(
|
||||||
|
OpenThermRequestType::READ_DATA,
|
||||||
|
OpenThermMessageID::CHPumpStarts,
|
||||||
|
0
|
||||||
|
));
|
||||||
|
|
||||||
|
if (!CustomOpenTherm::isValidResponse(response)) {
|
||||||
|
return false;
|
||||||
|
|
||||||
|
} else if (!CustomOpenTherm::isValidResponseId(response, OpenThermMessageID::CHPumpStarts)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
vars.slave.stats.heatingPumpStarts = CustomOpenTherm::getUInt(response);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool updateDhwPumpStarts() {
|
||||||
|
const unsigned long response = this->instance->sendRequest(CustomOpenTherm::buildRequest(
|
||||||
|
OpenThermRequestType::READ_DATA,
|
||||||
|
OpenThermMessageID::DHWPumpValveStarts,
|
||||||
|
0
|
||||||
|
));
|
||||||
|
|
||||||
|
if (!CustomOpenTherm::isValidResponse(response)) {
|
||||||
|
return false;
|
||||||
|
|
||||||
|
} else if (!CustomOpenTherm::isValidResponseId(response, OpenThermMessageID::DHWPumpValveStarts)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
vars.slave.stats.dhwPumpStarts = CustomOpenTherm::getUInt(response);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool updateBurnerHours() {
|
||||||
|
const unsigned long response = this->instance->sendRequest(CustomOpenTherm::buildRequest(
|
||||||
|
OpenThermRequestType::READ_DATA,
|
||||||
|
OpenThermMessageID::BurnerOperationHours,
|
||||||
|
0
|
||||||
|
));
|
||||||
|
|
||||||
|
if (!CustomOpenTherm::isValidResponse(response)) {
|
||||||
|
return false;
|
||||||
|
|
||||||
|
} else if (!CustomOpenTherm::isValidResponseId(response, OpenThermMessageID::BurnerOperationHours)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
vars.slave.stats.burnerHours = CustomOpenTherm::getUInt(response);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool updateDhwBurnerHours() {
|
||||||
|
const unsigned long response = this->instance->sendRequest(CustomOpenTherm::buildRequest(
|
||||||
|
OpenThermRequestType::READ_DATA,
|
||||||
|
OpenThermMessageID::DHWBurnerOperationHours,
|
||||||
|
0
|
||||||
|
));
|
||||||
|
|
||||||
|
if (!CustomOpenTherm::isValidResponse(response)) {
|
||||||
|
return false;
|
||||||
|
|
||||||
|
} else if (!CustomOpenTherm::isValidResponseId(response, OpenThermMessageID::DHWBurnerOperationHours)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
vars.slave.stats.dhwBurnerHours = CustomOpenTherm::getUInt(response);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool updateHeatingPumpHours() {
|
||||||
|
const unsigned long response = this->instance->sendRequest(CustomOpenTherm::buildRequest(
|
||||||
|
OpenThermRequestType::READ_DATA,
|
||||||
|
OpenThermMessageID::CHPumpOperationHours,
|
||||||
|
0
|
||||||
|
));
|
||||||
|
|
||||||
|
if (!CustomOpenTherm::isValidResponse(response)) {
|
||||||
|
return false;
|
||||||
|
|
||||||
|
} else if (!CustomOpenTherm::isValidResponseId(response, OpenThermMessageID::CHPumpOperationHours)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
vars.slave.stats.heatingPumpHours = CustomOpenTherm::getUInt(response);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool updateDhwPumpHours() {
|
||||||
|
const unsigned long response = this->instance->sendRequest(CustomOpenTherm::buildRequest(
|
||||||
|
OpenThermRequestType::READ_DATA,
|
||||||
|
OpenThermMessageID::DHWPumpValveOperationHours,
|
||||||
|
0
|
||||||
|
));
|
||||||
|
|
||||||
|
if (!CustomOpenTherm::isValidResponse(response)) {
|
||||||
|
return false;
|
||||||
|
|
||||||
|
} else if (!CustomOpenTherm::isValidResponseId(response, OpenThermMessageID::DHWPumpValveOperationHours)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
vars.slave.stats.dhwPumpHours = CustomOpenTherm::getUInt(response);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
bool updateModulationLevel() {
|
bool updateModulationLevel() {
|
||||||
const unsigned long response = this->instance->sendRequest(CustomOpenTherm::buildRequest(
|
const unsigned long response = this->instance->sendRequest(CustomOpenTherm::buildRequest(
|
||||||
OpenThermRequestType::READ_DATA,
|
OpenThermRequestType::READ_DATA,
|
||||||
|
|||||||
@@ -60,11 +60,11 @@ protected:
|
|||||||
this->hysteresis();
|
this->hysteresis();
|
||||||
|
|
||||||
vars.master.heating.targetTemp = settings.heating.target;
|
vars.master.heating.targetTemp = settings.heating.target;
|
||||||
vars.master.heating.setpointTemp = constrain(
|
vars.master.heating.setpointTemp = roundf(constrain(
|
||||||
this->getHeatingSetpointTemp(),
|
this->getHeatingSetpointTemp(),
|
||||||
this->getHeatingMinSetpointTemp(),
|
this->getHeatingMinSetpointTemp(),
|
||||||
this->getHeatingMaxSetpointTemp()
|
this->getHeatingMaxSetpointTemp()
|
||||||
);
|
), 0);
|
||||||
|
|
||||||
Sensors::setValueByType(
|
Sensors::setValueByType(
|
||||||
Sensors::Type::HEATING_SETPOINT_TEMP, vars.master.heating.setpointTemp,
|
Sensors::Type::HEATING_SETPOINT_TEMP, vars.master.heating.setpointTemp,
|
||||||
@@ -213,7 +213,8 @@ protected:
|
|||||||
}*/
|
}*/
|
||||||
|
|
||||||
float error = pidRegulator.setpoint - pidRegulator.input;
|
float error = pidRegulator.setpoint - pidRegulator.input;
|
||||||
bool hasDeadband = (error > -(settings.pid.deadband.thresholdHigh))
|
bool hasDeadband = settings.pid.deadband.enabled
|
||||||
|
&& (error > -(settings.pid.deadband.thresholdHigh))
|
||||||
&& (error < settings.pid.deadband.thresholdLow);
|
&& (error < settings.pid.deadband.thresholdLow);
|
||||||
|
|
||||||
if (hasDeadband) {
|
if (hasDeadband) {
|
||||||
|
|||||||
@@ -26,6 +26,15 @@ public:
|
|||||||
OT_FAN_SPEED_SETPOINT = 17,
|
OT_FAN_SPEED_SETPOINT = 17,
|
||||||
OT_FAN_SPEED_CURRENT = 18,
|
OT_FAN_SPEED_CURRENT = 18,
|
||||||
|
|
||||||
|
OT_BURNER_STARTS = 19,
|
||||||
|
OT_DHW_BURNER_STARTS = 20,
|
||||||
|
OT_HEATING_PUMP_STARTS = 21,
|
||||||
|
OT_DHW_PUMP_STARTS = 22,
|
||||||
|
OT_BURNER_HOURS = 23,
|
||||||
|
OT_DHW_BURNER_HOURS = 24,
|
||||||
|
OT_HEATING_PUMP_HOURS = 25,
|
||||||
|
OT_DHW_PUMP_HOURS = 26,
|
||||||
|
|
||||||
NTC_10K_TEMP = 50,
|
NTC_10K_TEMP = 50,
|
||||||
DALLAS_TEMP = 51,
|
DALLAS_TEMP = 51,
|
||||||
BLUETOOTH = 52,
|
BLUETOOTH = 52,
|
||||||
@@ -46,6 +55,7 @@ public:
|
|||||||
EXHAUST_TEMP = 7,
|
EXHAUST_TEMP = 7,
|
||||||
MODULATION_LEVEL = 8,
|
MODULATION_LEVEL = 8,
|
||||||
|
|
||||||
|
NUMBER = 247,
|
||||||
POWER_FACTOR = 248,
|
POWER_FACTOR = 248,
|
||||||
POWER = 249,
|
POWER = 249,
|
||||||
FAN_SPEED = 250,
|
FAN_SPEED = 250,
|
||||||
@@ -128,7 +138,7 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
uint8_t amount = 0;
|
uint8_t amount = 0;
|
||||||
for (uint8_t id = 0; id < getMaxSensorId(); id++) {
|
for (uint8_t id = 0; id <= getMaxSensorId(); id++) {
|
||||||
if (settings[id].type == type && (!onlyEnabled || settings[id].enabled)) {
|
if (settings[id].type == type && (!onlyEnabled || settings[id].enabled)) {
|
||||||
amount++;
|
amount++;
|
||||||
}
|
}
|
||||||
@@ -142,7 +152,7 @@ public:
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (uint8_t id = 0; id < getMaxSensorId(); id++) {
|
for (uint8_t id = 0; id <= getMaxSensorId(); id++) {
|
||||||
if (strcmp(settings[id].name, name) == 0) {
|
if (strcmp(settings[id].name, name) == 0) {
|
||||||
return id;
|
return id;
|
||||||
}
|
}
|
||||||
@@ -157,7 +167,7 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
String refObjectId;
|
String refObjectId;
|
||||||
for (uint8_t id = 0; id < getMaxSensorId(); id++) {
|
for (uint8_t id = 0; id <= getMaxSensorId(); id++) {
|
||||||
Sensors::makeObjectId(refObjectId, settings[id].name);
|
Sensors::makeObjectId(refObjectId, settings[id].name);
|
||||||
if (refObjectId.equals(objectId)) {
|
if (refObjectId.equals(objectId)) {
|
||||||
return id;
|
return id;
|
||||||
@@ -237,7 +247,7 @@ public:
|
|||||||
uint8_t updated = 0;
|
uint8_t updated = 0;
|
||||||
|
|
||||||
// read sensors data for current instance
|
// read sensors data for current instance
|
||||||
for (uint8_t sensorId = 0; sensorId < getMaxSensorId(); sensorId++) {
|
for (uint8_t sensorId = 0; sensorId <= getMaxSensorId(); sensorId++) {
|
||||||
auto& sSensor = settings[sensorId];
|
auto& sSensor = settings[sensorId];
|
||||||
|
|
||||||
// only target & valid sensors
|
// only target & valid sensors
|
||||||
@@ -301,7 +311,7 @@ public:
|
|||||||
uint8_t updated = 0;
|
uint8_t updated = 0;
|
||||||
|
|
||||||
// read sensors data for current instance
|
// read sensors data for current instance
|
||||||
for (uint8_t sensorId = 0; sensorId < getMaxSensorId(); sensorId++) {
|
for (uint8_t sensorId = 0; sensorId <= getMaxSensorId(); sensorId++) {
|
||||||
auto& sSensor = settings[sensorId];
|
auto& sSensor = settings[sensorId];
|
||||||
|
|
||||||
// only target & valid sensors
|
// only target & valid sensors
|
||||||
@@ -324,13 +334,13 @@ public:
|
|||||||
|
|
||||||
uint8_t valueId = (uint8_t) valueType;
|
uint8_t valueId = (uint8_t) valueType;
|
||||||
if (!isValidValueId(valueId)) {
|
if (!isValidValueId(valueId)) {
|
||||||
return false;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
float value = 0.0f;
|
float value = 0.0f;
|
||||||
uint8_t amount = 0;
|
uint8_t amount = 0;
|
||||||
|
|
||||||
for (uint8_t id = 0; id < getMaxSensorId(); id++) {
|
for (uint8_t id = 0; id <= getMaxSensorId(); id++) {
|
||||||
auto& sSensor = settings[id];
|
auto& sSensor = settings[id];
|
||||||
auto& rSensor = results[id];
|
auto& rSensor = results[id];
|
||||||
|
|
||||||
@@ -356,7 +366,7 @@ public:
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (uint8_t id = 0; id < getMaxSensorId(); id++) {
|
for (uint8_t id = 0; id <= getMaxSensorId(); id++) {
|
||||||
if (settings[id].purpose == purpose && results[id].connected) {
|
if (settings[id].purpose == purpose && results[id].connected) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -385,7 +385,7 @@ protected:
|
|||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
||||||
const float sensorResistance = value > 0.001f
|
const float sensorResistance = value > 1
|
||||||
? DEFAULT_NTC_REF_RESISTANCE / (DEFAULT_NTC_VREF / (float) value - 1.0f)
|
? DEFAULT_NTC_REF_RESISTANCE / (DEFAULT_NTC_VREF / (float) value - 1.0f)
|
||||||
: 0.0f;
|
: 0.0f;
|
||||||
const float rawTemp = 1.0f / (
|
const float rawTemp = 1.0f / (
|
||||||
@@ -577,7 +577,7 @@ protected:
|
|||||||
|
|
||||||
bool subscribeToBleDevice(const uint8_t sensorId, NimBLEClient* pClient) {
|
bool subscribeToBleDevice(const uint8_t sensorId, NimBLEClient* pClient) {
|
||||||
auto& sSensor = Sensors::settings[sensorId];
|
auto& sSensor = Sensors::settings[sensorId];
|
||||||
auto pAddress = pClient->getPeerAddress().toString().c_str();
|
auto pAddress = pClient->getPeerAddress().toString();
|
||||||
|
|
||||||
NimBLERemoteService* pService = nullptr;
|
NimBLERemoteService* pService = nullptr;
|
||||||
NimBLERemoteCharacteristic* pChar = nullptr;
|
NimBLERemoteCharacteristic* pChar = nullptr;
|
||||||
@@ -588,13 +588,13 @@ protected:
|
|||||||
if (!pService) {
|
if (!pService) {
|
||||||
Log.straceln(
|
Log.straceln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': failed to find env service (%s) on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': failed to find env service (%s) on device %s"),
|
||||||
sensorId, sSensor.name, serviceUuid.toString().c_str(), pAddress
|
sensorId, sSensor.name, serviceUuid.toString().c_str(), pAddress.c_str()
|
||||||
);
|
);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
Log.straceln(
|
Log.straceln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': found env service (%s) on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': found env service (%s) on device %s"),
|
||||||
sensorId, sSensor.name, serviceUuid.toString().c_str(), pAddress
|
sensorId, sSensor.name, serviceUuid.toString().c_str(), pAddress.c_str()
|
||||||
);
|
);
|
||||||
|
|
||||||
// 0x2A6E - Notify temperature x0.01C (pvvx)
|
// 0x2A6E - Notify temperature x0.01C (pvvx)
|
||||||
@@ -606,7 +606,7 @@ protected:
|
|||||||
if (pChar && (pChar->canNotify() || pChar->canIndicate())) {
|
if (pChar && (pChar->canNotify() || pChar->canIndicate())) {
|
||||||
Log.straceln(
|
Log.straceln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': found temp char (%s) in env service on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': found temp char (%s) in env service on device %s"),
|
||||||
sensorId, sSensor.name, charUuid.toString().c_str(), pAddress
|
sensorId, sSensor.name, charUuid.toString().c_str(), pAddress.c_str()
|
||||||
);
|
);
|
||||||
|
|
||||||
pChar->unsubscribe();
|
pChar->unsubscribe();
|
||||||
@@ -661,14 +661,14 @@ protected:
|
|||||||
Log.straceln(
|
Log.straceln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': subscribed to temp char (%s) in env service on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': subscribed to temp char (%s) in env service on device %s"),
|
||||||
sensorId, sSensor.name,
|
sensorId, sSensor.name,
|
||||||
charUuid.toString().c_str(), pAddress
|
charUuid.toString().c_str(), pAddress.c_str()
|
||||||
);
|
);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
Log.swarningln(
|
Log.swarningln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': failed to subscribe to temp char (%s) in env service on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': failed to subscribe to temp char (%s) in env service on device %s"),
|
||||||
sensorId, sSensor.name,
|
sensorId, sSensor.name,
|
||||||
charUuid.toString().c_str(), pAddress
|
charUuid.toString().c_str(), pAddress.c_str()
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -683,7 +683,7 @@ protected:
|
|||||||
if (pChar && (pChar->canNotify() || pChar->canIndicate())) {
|
if (pChar && (pChar->canNotify() || pChar->canIndicate())) {
|
||||||
Log.straceln(
|
Log.straceln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': found temp char (%s) in env service on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': found temp char (%s) in env service on device %s"),
|
||||||
sensorId, sSensor.name, charUuid.toString().c_str(), pAddress
|
sensorId, sSensor.name, charUuid.toString().c_str(), pAddress.c_str()
|
||||||
);
|
);
|
||||||
|
|
||||||
pChar->unsubscribe();
|
pChar->unsubscribe();
|
||||||
@@ -738,14 +738,14 @@ protected:
|
|||||||
Log.straceln(
|
Log.straceln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': subscribed to temp char (%s) in env service on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': subscribed to temp char (%s) in env service on device %s"),
|
||||||
sensorId, sSensor.name,
|
sensorId, sSensor.name,
|
||||||
charUuid.toString().c_str(), pAddress
|
charUuid.toString().c_str(), pAddress.c_str()
|
||||||
);
|
);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
Log.swarningln(
|
Log.swarningln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': failed to subscribe to temp char (%s) in env service on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': failed to subscribe to temp char (%s) in env service on device %s"),
|
||||||
sensorId, sSensor.name,
|
sensorId, sSensor.name,
|
||||||
charUuid.toString().c_str(), pAddress
|
charUuid.toString().c_str(), pAddress.c_str()
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -754,7 +754,7 @@ protected:
|
|||||||
if (!tempNotifyCreated) {
|
if (!tempNotifyCreated) {
|
||||||
Log.swarningln(
|
Log.swarningln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': not found supported temp chars in env service on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': not found supported temp chars in env service on device %s"),
|
||||||
sensorId, sSensor.name, pAddress
|
sensorId, sSensor.name, pAddress.c_str()
|
||||||
);
|
);
|
||||||
|
|
||||||
pClient->disconnect();
|
pClient->disconnect();
|
||||||
@@ -772,7 +772,7 @@ protected:
|
|||||||
if (pChar && (pChar->canNotify() || pChar->canIndicate())) {
|
if (pChar && (pChar->canNotify() || pChar->canIndicate())) {
|
||||||
Log.straceln(
|
Log.straceln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': found humidity char (%s) in env service on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': found humidity char (%s) in env service on device %s"),
|
||||||
sensorId, sSensor.name, charUuid.toString().c_str(), pAddress
|
sensorId, sSensor.name, charUuid.toString().c_str(), pAddress.c_str()
|
||||||
);
|
);
|
||||||
|
|
||||||
pChar->unsubscribe();
|
pChar->unsubscribe();
|
||||||
@@ -827,14 +827,14 @@ protected:
|
|||||||
Log.straceln(
|
Log.straceln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': subscribed to humidity char (%s) in env service on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': subscribed to humidity char (%s) in env service on device %s"),
|
||||||
sensorId, sSensor.name,
|
sensorId, sSensor.name,
|
||||||
charUuid.toString().c_str(), pAddress
|
charUuid.toString().c_str(), pAddress.c_str()
|
||||||
);
|
);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
Log.swarningln(
|
Log.swarningln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': failed to subscribe to humidity char (%s) in env service on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': failed to subscribe to humidity char (%s) in env service on device %s"),
|
||||||
sensorId, sSensor.name,
|
sensorId, sSensor.name,
|
||||||
charUuid.toString().c_str(), pAddress
|
charUuid.toString().c_str(), pAddress.c_str()
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -843,7 +843,7 @@ protected:
|
|||||||
if (!humidityNotifyCreated) {
|
if (!humidityNotifyCreated) {
|
||||||
Log.swarningln(
|
Log.swarningln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': not found supported humidity chars in env service on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': not found supported humidity chars in env service on device %s"),
|
||||||
sensorId, sSensor.name, pAddress
|
sensorId, sSensor.name, pAddress.c_str()
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -857,13 +857,13 @@ protected:
|
|||||||
if (!pService) {
|
if (!pService) {
|
||||||
Log.straceln(
|
Log.straceln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': failed to find battery service (%s) on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': failed to find battery service (%s) on device %s"),
|
||||||
sensorId, sSensor.name, serviceUuid.toString().c_str(), pAddress
|
sensorId, sSensor.name, serviceUuid.toString().c_str(), pAddress.c_str()
|
||||||
);
|
);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
Log.straceln(
|
Log.straceln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': found battery service (%s) on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': found battery service (%s) on device %s"),
|
||||||
sensorId, sSensor.name, serviceUuid.toString().c_str(), pAddress
|
sensorId, sSensor.name, serviceUuid.toString().c_str(), pAddress.c_str()
|
||||||
);
|
);
|
||||||
|
|
||||||
// 0x2A19 - Notify the battery charge level 0..99% (pvvx)
|
// 0x2A19 - Notify the battery charge level 0..99% (pvvx)
|
||||||
@@ -875,7 +875,7 @@ protected:
|
|||||||
if (pChar && (pChar->canNotify() || pChar->canIndicate())) {
|
if (pChar && (pChar->canNotify() || pChar->canIndicate())) {
|
||||||
Log.straceln(
|
Log.straceln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': found battery char (%s) in battery service on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': found battery char (%s) in battery service on device %s"),
|
||||||
sensorId, sSensor.name, charUuid.toString().c_str(), pAddress
|
sensorId, sSensor.name, charUuid.toString().c_str(), pAddress.c_str()
|
||||||
);
|
);
|
||||||
|
|
||||||
pChar->unsubscribe();
|
pChar->unsubscribe();
|
||||||
@@ -930,14 +930,14 @@ protected:
|
|||||||
Log.straceln(
|
Log.straceln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': subscribed to battery char (%s) in battery service on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': subscribed to battery char (%s) in battery service on device %s"),
|
||||||
sensorId, sSensor.name,
|
sensorId, sSensor.name,
|
||||||
charUuid.toString().c_str(), pAddress
|
charUuid.toString().c_str(), pAddress.c_str()
|
||||||
);
|
);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
Log.swarningln(
|
Log.swarningln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': failed to subscribe to battery char (%s) in battery service on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': failed to subscribe to battery char (%s) in battery service on device %s"),
|
||||||
sensorId, sSensor.name,
|
sensorId, sSensor.name,
|
||||||
charUuid.toString().c_str(), pAddress
|
charUuid.toString().c_str(), pAddress.c_str()
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -946,7 +946,7 @@ protected:
|
|||||||
if (!batteryNotifyCreated) {
|
if (!batteryNotifyCreated) {
|
||||||
Log.swarningln(
|
Log.swarningln(
|
||||||
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': not found supported battery chars in battery service on device %s"),
|
FPSTR(L_SENSORS_BLE), F("Sensor #%hhu '%s': not found supported battery chars in battery service on device %s"),
|
||||||
sensorId, sSensor.name, pAddress
|
sensorId, sSensor.name, pAddress.c_str()
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -12,13 +12,13 @@ struct NetworkSettings {
|
|||||||
struct {
|
struct {
|
||||||
char ssid[33] = DEFAULT_AP_SSID;
|
char ssid[33] = DEFAULT_AP_SSID;
|
||||||
char password[65] = DEFAULT_AP_PASSWORD;
|
char password[65] = DEFAULT_AP_PASSWORD;
|
||||||
byte channel = 6;
|
uint8_t channel = 6;
|
||||||
} ap;
|
} ap;
|
||||||
|
|
||||||
struct {
|
struct {
|
||||||
char ssid[33] = DEFAULT_STA_SSID;
|
char ssid[33] = DEFAULT_STA_SSID;
|
||||||
char password[65] = DEFAULT_STA_PASSWORD;
|
char password[65] = DEFAULT_STA_PASSWORD;
|
||||||
byte channel = 0;
|
uint8_t channel = 0;
|
||||||
} sta;
|
} sta;
|
||||||
} networkSettings;
|
} networkSettings;
|
||||||
|
|
||||||
@@ -42,7 +42,7 @@ struct Settings {
|
|||||||
} ntp;
|
} ntp;
|
||||||
|
|
||||||
UnitSystem unitSystem = UnitSystem::METRIC;
|
UnitSystem unitSystem = UnitSystem::METRIC;
|
||||||
byte statusLedGpio = DEFAULT_STATUS_LED_GPIO;
|
uint8_t statusLedGpio = DEFAULT_STATUS_LED_GPIO;
|
||||||
} system;
|
} system;
|
||||||
|
|
||||||
struct {
|
struct {
|
||||||
@@ -54,12 +54,11 @@ struct Settings {
|
|||||||
|
|
||||||
struct {
|
struct {
|
||||||
UnitSystem unitSystem = UnitSystem::METRIC;
|
UnitSystem unitSystem = UnitSystem::METRIC;
|
||||||
byte inGpio = DEFAULT_OT_IN_GPIO;
|
uint8_t inGpio = DEFAULT_OT_IN_GPIO;
|
||||||
byte outGpio = DEFAULT_OT_OUT_GPIO;
|
uint8_t outGpio = DEFAULT_OT_OUT_GPIO;
|
||||||
byte rxLedGpio = DEFAULT_OT_RX_LED_GPIO;
|
uint8_t rxLedGpio = DEFAULT_OT_RX_LED_GPIO;
|
||||||
uint8_t memberId = 0;
|
uint8_t memberId = 0;
|
||||||
uint8_t flags = 0;
|
uint8_t flags = 0;
|
||||||
uint8_t maxModulation = 100;
|
|
||||||
float minPower = 0.0f;
|
float minPower = 0.0f;
|
||||||
float maxPower = 0.0f;
|
float maxPower = 0.0f;
|
||||||
|
|
||||||
@@ -72,9 +71,13 @@ struct Settings {
|
|||||||
bool heatingToCh2 = false;
|
bool heatingToCh2 = false;
|
||||||
bool dhwToCh2 = false;
|
bool dhwToCh2 = false;
|
||||||
bool dhwBlocking = false;
|
bool dhwBlocking = false;
|
||||||
bool modulationSyncWithHeating = false;
|
bool dhwStateAsDhwBlocking = false;
|
||||||
bool maxTempSyncWithTargetTemp = true;
|
bool maxTempSyncWithTargetTemp = true;
|
||||||
bool getMinMaxTemp = true;
|
bool getMinMaxTemp = true;
|
||||||
|
bool ignoreDiagState = false;
|
||||||
|
bool autoFaultReset = false;
|
||||||
|
bool autoDiagReset = false;
|
||||||
|
bool setDateAndTime = false;
|
||||||
bool nativeHeatingControl = false;
|
bool nativeHeatingControl = false;
|
||||||
bool immergasFix = false;
|
bool immergasFix = false;
|
||||||
} options;
|
} options;
|
||||||
@@ -102,15 +105,32 @@ struct Settings {
|
|||||||
float target = DEFAULT_HEATING_TARGET_TEMP;
|
float target = DEFAULT_HEATING_TARGET_TEMP;
|
||||||
float hysteresis = 0.5f;
|
float hysteresis = 0.5f;
|
||||||
float turboFactor = 7.5f;
|
float turboFactor = 7.5f;
|
||||||
byte minTemp = DEFAULT_HEATING_MIN_TEMP;
|
uint8_t minTemp = DEFAULT_HEATING_MIN_TEMP;
|
||||||
byte maxTemp = DEFAULT_HEATING_MAX_TEMP;
|
uint8_t maxTemp = DEFAULT_HEATING_MAX_TEMP;
|
||||||
|
uint8_t maxModulation = 100;
|
||||||
|
|
||||||
|
struct {
|
||||||
|
uint8_t highTemp = 95;
|
||||||
|
uint8_t lowTemp = 90;
|
||||||
|
} overheatProtection;
|
||||||
|
|
||||||
|
struct {
|
||||||
|
uint8_t lowTemp = 10;
|
||||||
|
unsigned short thresholdTime = 600;
|
||||||
|
} freezeProtection;
|
||||||
} heating;
|
} heating;
|
||||||
|
|
||||||
struct {
|
struct {
|
||||||
bool enabled = true;
|
bool enabled = true;
|
||||||
float target = DEFAULT_DHW_TARGET_TEMP;
|
float target = DEFAULT_DHW_TARGET_TEMP;
|
||||||
byte minTemp = DEFAULT_DHW_MIN_TEMP;
|
uint8_t minTemp = DEFAULT_DHW_MIN_TEMP;
|
||||||
byte maxTemp = DEFAULT_DHW_MAX_TEMP;
|
uint8_t maxTemp = DEFAULT_DHW_MAX_TEMP;
|
||||||
|
uint8_t maxModulation = 100;
|
||||||
|
|
||||||
|
struct {
|
||||||
|
uint8_t highTemp = 95;
|
||||||
|
uint8_t lowTemp = 90;
|
||||||
|
} overheatProtection;
|
||||||
} dhw;
|
} dhw;
|
||||||
|
|
||||||
struct {
|
struct {
|
||||||
@@ -141,7 +161,7 @@ struct Settings {
|
|||||||
|
|
||||||
struct {
|
struct {
|
||||||
bool use = false;
|
bool use = false;
|
||||||
byte gpio = DEFAULT_EXT_PUMP_GPIO;
|
uint8_t gpio = DEFAULT_EXT_PUMP_GPIO;
|
||||||
unsigned short postCirculationTime = 600;
|
unsigned short postCirculationTime = 600;
|
||||||
unsigned int antiStuckInterval = 2592000;
|
unsigned int antiStuckInterval = 2592000;
|
||||||
unsigned short antiStuckTime = 300;
|
unsigned short antiStuckTime = 300;
|
||||||
@@ -150,15 +170,15 @@ struct Settings {
|
|||||||
struct {
|
struct {
|
||||||
struct {
|
struct {
|
||||||
bool enabled = false;
|
bool enabled = false;
|
||||||
byte gpio = GPIO_IS_NOT_CONFIGURED;
|
uint8_t gpio = GPIO_IS_NOT_CONFIGURED;
|
||||||
byte invertState = false;
|
bool invertState = false;
|
||||||
unsigned short thresholdTime = 60;
|
unsigned short thresholdTime = 60;
|
||||||
} input;
|
} input;
|
||||||
|
|
||||||
struct {
|
struct {
|
||||||
bool enabled = false;
|
bool enabled = false;
|
||||||
byte gpio = GPIO_IS_NOT_CONFIGURED;
|
uint8_t gpio = GPIO_IS_NOT_CONFIGURED;
|
||||||
byte invertState = false;
|
bool invertState = false;
|
||||||
unsigned short thresholdTime = 60;
|
unsigned short thresholdTime = 60;
|
||||||
bool onFault = true;
|
bool onFault = true;
|
||||||
bool onLossConnection = true;
|
bool onLossConnection = true;
|
||||||
@@ -275,6 +295,7 @@ struct Variables {
|
|||||||
bool blocking = false;
|
bool blocking = false;
|
||||||
bool enabled = false;
|
bool enabled = false;
|
||||||
bool indoorTempControl = false;
|
bool indoorTempControl = false;
|
||||||
|
bool overheat = false;
|
||||||
float setpointTemp = 0.0f;
|
float setpointTemp = 0.0f;
|
||||||
float targetTemp = 0.0f;
|
float targetTemp = 0.0f;
|
||||||
float currentTemp = 0.0f;
|
float currentTemp = 0.0f;
|
||||||
@@ -287,6 +308,7 @@ struct Variables {
|
|||||||
|
|
||||||
struct {
|
struct {
|
||||||
bool enabled = false;
|
bool enabled = false;
|
||||||
|
bool overheat = false;
|
||||||
float targetTemp = 0.0f;
|
float targetTemp = 0.0f;
|
||||||
float currentTemp = 0.0f;
|
float currentTemp = 0.0f;
|
||||||
float returnTemp = 0.0f;
|
float returnTemp = 0.0f;
|
||||||
@@ -350,6 +372,17 @@ struct Variables {
|
|||||||
uint16_t supply = 0;
|
uint16_t supply = 0;
|
||||||
} fanSpeed;
|
} fanSpeed;
|
||||||
|
|
||||||
|
struct {
|
||||||
|
uint16_t burnerStarts = 0;
|
||||||
|
uint16_t dhwBurnerStarts = 0;
|
||||||
|
uint16_t heatingPumpStarts = 0;
|
||||||
|
uint16_t dhwPumpStarts = 0;
|
||||||
|
uint16_t burnerHours = 0;
|
||||||
|
uint16_t dhwBurnerHours = 0;
|
||||||
|
uint16_t heatingPumpHours = 0;
|
||||||
|
uint16_t dhwPumpHours = 0;
|
||||||
|
} stats;
|
||||||
|
|
||||||
struct {
|
struct {
|
||||||
bool active = false;
|
bool active = false;
|
||||||
bool enabled = false;
|
bool enabled = false;
|
||||||
@@ -375,6 +408,7 @@ struct Variables {
|
|||||||
} dhw;
|
} dhw;
|
||||||
|
|
||||||
struct {
|
struct {
|
||||||
|
bool active = false;
|
||||||
bool enabled = false;
|
bool enabled = false;
|
||||||
float targetTemp = 0.0f;
|
float targetTemp = 0.0f;
|
||||||
float currentTemp = 0.0f;
|
float currentTemp = 0.0f;
|
||||||
|
|||||||
@@ -16,7 +16,7 @@
|
|||||||
|
|
||||||
#define THERMOSTAT_INDOOR_DEFAULT_TEMP 20
|
#define THERMOSTAT_INDOOR_DEFAULT_TEMP 20
|
||||||
#define THERMOSTAT_INDOOR_MIN_TEMP 5
|
#define THERMOSTAT_INDOOR_MIN_TEMP 5
|
||||||
#define THERMOSTAT_INDOOR_MAX_TEMP 30
|
#define THERMOSTAT_INDOOR_MAX_TEMP 40
|
||||||
|
|
||||||
#define DEFAULT_NTC_NOMINAL_RESISTANCE 10000.0f
|
#define DEFAULT_NTC_NOMINAL_RESISTANCE 10000.0f
|
||||||
#define DEFAULT_NTC_NOMINAL_TEMP 25.0f
|
#define DEFAULT_NTC_NOMINAL_TEMP 25.0f
|
||||||
|
|||||||
@@ -42,6 +42,8 @@ const char S_ANTI_STUCK_TIME[] PROGMEM = "antiStuckTime";
|
|||||||
const char S_AP[] PROGMEM = "ap";
|
const char S_AP[] PROGMEM = "ap";
|
||||||
const char S_APP_VERSION[] PROGMEM = "appVersion";
|
const char S_APP_VERSION[] PROGMEM = "appVersion";
|
||||||
const char S_AUTH[] PROGMEM = "auth";
|
const char S_AUTH[] PROGMEM = "auth";
|
||||||
|
const char S_AUTO_DIAG_RESET[] PROGMEM = "autoDiagReset";
|
||||||
|
const char S_AUTO_FAULT_RESET[] PROGMEM = "autoFaultReset";
|
||||||
const char S_BACKTRACE[] PROGMEM = "backtrace";
|
const char S_BACKTRACE[] PROGMEM = "backtrace";
|
||||||
const char S_BATTERY[] PROGMEM = "battery";
|
const char S_BATTERY[] PROGMEM = "battery";
|
||||||
const char S_BAUDRATE[] PROGMEM = "baudrate";
|
const char S_BAUDRATE[] PROGMEM = "baudrate";
|
||||||
@@ -66,6 +68,7 @@ const char S_DATE[] PROGMEM = "date";
|
|||||||
const char S_DEADBAND[] PROGMEM = "deadband";
|
const char S_DEADBAND[] PROGMEM = "deadband";
|
||||||
const char S_DHW[] PROGMEM = "dhw";
|
const char S_DHW[] PROGMEM = "dhw";
|
||||||
const char S_DHW_BLOCKING[] PROGMEM = "dhwBlocking";
|
const char S_DHW_BLOCKING[] PROGMEM = "dhwBlocking";
|
||||||
|
const char S_DHW_STATE_AS_DHW_BLOCKING[] PROGMEM = "dhwStateAsDhwBlocking";
|
||||||
const char S_DHW_SUPPORT[] PROGMEM = "dhwSupport";
|
const char S_DHW_SUPPORT[] PROGMEM = "dhwSupport";
|
||||||
const char S_DHW_TO_CH2[] PROGMEM = "dhwToCh2";
|
const char S_DHW_TO_CH2[] PROGMEM = "dhwToCh2";
|
||||||
const char S_DIAG[] PROGMEM = "diag";
|
const char S_DIAG[] PROGMEM = "diag";
|
||||||
@@ -81,6 +84,7 @@ const char S_EQUITHERM[] PROGMEM = "equitherm";
|
|||||||
const char S_EXTERNAL_PUMP[] PROGMEM = "externalPump";
|
const char S_EXTERNAL_PUMP[] PROGMEM = "externalPump";
|
||||||
const char S_FACTOR[] PROGMEM = "factor";
|
const char S_FACTOR[] PROGMEM = "factor";
|
||||||
const char S_FAULT[] PROGMEM = "fault";
|
const char S_FAULT[] PROGMEM = "fault";
|
||||||
|
const char S_FREEZE_PROTECTION[] PROGMEM = "freezeProtection";
|
||||||
const char S_FILTERING[] PROGMEM = "filtering";
|
const char S_FILTERING[] PROGMEM = "filtering";
|
||||||
const char S_FILTERING_FACTOR[] PROGMEM = "filteringFactor";
|
const char S_FILTERING_FACTOR[] PROGMEM = "filteringFactor";
|
||||||
const char S_FLAGS[] PROGMEM = "flags";
|
const char S_FLAGS[] PROGMEM = "flags";
|
||||||
@@ -96,11 +100,13 @@ const char S_HEATING[] PROGMEM = "heating";
|
|||||||
const char S_HEATING_TO_CH2[] PROGMEM = "heatingToCh2";
|
const char S_HEATING_TO_CH2[] PROGMEM = "heatingToCh2";
|
||||||
const char S_HEATING_STATE_TO_SUMMER_WINTER_MODE[] PROGMEM = "heatingStateToSummerWinterMode";
|
const char S_HEATING_STATE_TO_SUMMER_WINTER_MODE[] PROGMEM = "heatingStateToSummerWinterMode";
|
||||||
const char S_HIDDEN[] PROGMEM = "hidden";
|
const char S_HIDDEN[] PROGMEM = "hidden";
|
||||||
|
const char S_HIGH_TEMP[] PROGMEM = "highTemp";
|
||||||
const char S_HOME_ASSISTANT_DISCOVERY[] PROGMEM = "homeAssistantDiscovery";
|
const char S_HOME_ASSISTANT_DISCOVERY[] PROGMEM = "homeAssistantDiscovery";
|
||||||
const char S_HOSTNAME[] PROGMEM = "hostname";
|
const char S_HOSTNAME[] PROGMEM = "hostname";
|
||||||
const char S_HUMIDITY[] PROGMEM = "humidity";
|
const char S_HUMIDITY[] PROGMEM = "humidity";
|
||||||
const char S_HYSTERESIS[] PROGMEM = "hysteresis";
|
const char S_HYSTERESIS[] PROGMEM = "hysteresis";
|
||||||
const char S_ID[] PROGMEM = "id";
|
const char S_ID[] PROGMEM = "id";
|
||||||
|
const char S_IGNORE_DIAG_STATE[] PROGMEM = "ignoreDiagState";
|
||||||
const char S_IMMERGAS_FIX[] PROGMEM = "immergasFix";
|
const char S_IMMERGAS_FIX[] PROGMEM = "immergasFix";
|
||||||
const char S_INDOOR_TEMP[] PROGMEM = "indoorTemp";
|
const char S_INDOOR_TEMP[] PROGMEM = "indoorTemp";
|
||||||
const char S_INDOOR_TEMP_CONTROL[] PROGMEM = "indoorTempControl";
|
const char S_INDOOR_TEMP_CONTROL[] PROGMEM = "indoorTempControl";
|
||||||
@@ -114,6 +120,7 @@ const char S_I_MULTIPLIER[] PROGMEM = "i_multiplier";
|
|||||||
const char S_K_FACTOR[] PROGMEM = "k_factor";
|
const char S_K_FACTOR[] PROGMEM = "k_factor";
|
||||||
const char S_LOGIN[] PROGMEM = "login";
|
const char S_LOGIN[] PROGMEM = "login";
|
||||||
const char S_LOG_LEVEL[] PROGMEM = "logLevel";
|
const char S_LOG_LEVEL[] PROGMEM = "logLevel";
|
||||||
|
const char S_LOW_TEMP[] PROGMEM = "lowTemp";
|
||||||
const char S_MAC[] PROGMEM = "mac";
|
const char S_MAC[] PROGMEM = "mac";
|
||||||
const char S_MASTER[] PROGMEM = "master";
|
const char S_MASTER[] PROGMEM = "master";
|
||||||
const char S_MAX[] PROGMEM = "max";
|
const char S_MAX[] PROGMEM = "max";
|
||||||
@@ -131,7 +138,6 @@ const char S_MIN_POWER[] PROGMEM = "minPower";
|
|||||||
const char S_MIN_TEMP[] PROGMEM = "minTemp";
|
const char S_MIN_TEMP[] PROGMEM = "minTemp";
|
||||||
const char S_MODEL[] PROGMEM = "model";
|
const char S_MODEL[] PROGMEM = "model";
|
||||||
const char S_MODULATION[] PROGMEM = "modulation";
|
const char S_MODULATION[] PROGMEM = "modulation";
|
||||||
const char S_MODULATION_SYNC_WITH_HEATING[] PROGMEM = "modulationSyncWithHeating";
|
|
||||||
const char S_MQTT[] PROGMEM = "mqtt";
|
const char S_MQTT[] PROGMEM = "mqtt";
|
||||||
const char S_NAME[] PROGMEM = "name";
|
const char S_NAME[] PROGMEM = "name";
|
||||||
const char S_NATIVE_HEATING_CONTROL[] PROGMEM = "nativeHeatingControl";
|
const char S_NATIVE_HEATING_CONTROL[] PROGMEM = "nativeHeatingControl";
|
||||||
@@ -147,6 +153,8 @@ const char S_OPTIONS[] PROGMEM = "options";
|
|||||||
const char S_OUTDOOR_TEMP[] PROGMEM = "outdoorTemp";
|
const char S_OUTDOOR_TEMP[] PROGMEM = "outdoorTemp";
|
||||||
const char S_OUT_GPIO[] PROGMEM = "outGpio";
|
const char S_OUT_GPIO[] PROGMEM = "outGpio";
|
||||||
const char S_OUTPUT[] PROGMEM = "output";
|
const char S_OUTPUT[] PROGMEM = "output";
|
||||||
|
const char S_OVERHEAT[] PROGMEM = "overheat";
|
||||||
|
const char S_OVERHEAT_PROTECTION[] PROGMEM = "overheatProtection";
|
||||||
const char S_PASSWORD[] PROGMEM = "password";
|
const char S_PASSWORD[] PROGMEM = "password";
|
||||||
const char S_PID[] PROGMEM = "pid";
|
const char S_PID[] PROGMEM = "pid";
|
||||||
const char S_PORT[] PROGMEM = "port";
|
const char S_PORT[] PROGMEM = "port";
|
||||||
@@ -173,6 +181,7 @@ const char S_SENSORS[] PROGMEM = "sensors";
|
|||||||
const char S_SERIAL[] PROGMEM = "serial";
|
const char S_SERIAL[] PROGMEM = "serial";
|
||||||
const char S_SERVER[] PROGMEM = "server";
|
const char S_SERVER[] PROGMEM = "server";
|
||||||
const char S_SETTINGS[] PROGMEM = "settings";
|
const char S_SETTINGS[] PROGMEM = "settings";
|
||||||
|
const char S_SET_DATE_AND_TIME[] PROGMEM = "setDateAndTime";
|
||||||
const char S_SIGNAL_QUALITY[] PROGMEM = "signalQuality";
|
const char S_SIGNAL_QUALITY[] PROGMEM = "signalQuality";
|
||||||
const char S_SIZE[] PROGMEM = "size";
|
const char S_SIZE[] PROGMEM = "size";
|
||||||
const char S_SLAVE[] PROGMEM = "slave";
|
const char S_SLAVE[] PROGMEM = "slave";
|
||||||
|
|||||||
179
src/utils.h
179
src/utils.h
@@ -72,7 +72,7 @@ time_t mkgmtime(const struct tm *ptm) {
|
|||||||
|
|
||||||
inline bool isDigit(const char* ptr) {
|
inline bool isDigit(const char* ptr) {
|
||||||
char* endPtr;
|
char* endPtr;
|
||||||
strtol(ptr, &endPtr, 10);
|
auto tmp = strtol(ptr, &endPtr, 10);
|
||||||
return *endPtr == 0;
|
return *endPtr == 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -449,7 +449,6 @@ void settingsToJson(const Settings& src, JsonVariant dst, bool safe = false) {
|
|||||||
opentherm[FPSTR(S_RX_LED_GPIO)] = src.opentherm.rxLedGpio;
|
opentherm[FPSTR(S_RX_LED_GPIO)] = src.opentherm.rxLedGpio;
|
||||||
opentherm[FPSTR(S_MEMBER_ID)] = src.opentherm.memberId;
|
opentherm[FPSTR(S_MEMBER_ID)] = src.opentherm.memberId;
|
||||||
opentherm[FPSTR(S_FLAGS)] = src.opentherm.flags;
|
opentherm[FPSTR(S_FLAGS)] = src.opentherm.flags;
|
||||||
opentherm[FPSTR(S_MAX_MODULATION)] = src.opentherm.maxModulation;
|
|
||||||
opentherm[FPSTR(S_MIN_POWER)] = roundf(src.opentherm.minPower, 2);
|
opentherm[FPSTR(S_MIN_POWER)] = roundf(src.opentherm.minPower, 2);
|
||||||
opentherm[FPSTR(S_MAX_POWER)] = roundf(src.opentherm.maxPower, 2);
|
opentherm[FPSTR(S_MAX_POWER)] = roundf(src.opentherm.maxPower, 2);
|
||||||
|
|
||||||
@@ -462,9 +461,13 @@ void settingsToJson(const Settings& src, JsonVariant dst, bool safe = false) {
|
|||||||
otOptions[FPSTR(S_HEATING_TO_CH2)] = src.opentherm.options.heatingToCh2;
|
otOptions[FPSTR(S_HEATING_TO_CH2)] = src.opentherm.options.heatingToCh2;
|
||||||
otOptions[FPSTR(S_DHW_TO_CH2)] = src.opentherm.options.dhwToCh2;
|
otOptions[FPSTR(S_DHW_TO_CH2)] = src.opentherm.options.dhwToCh2;
|
||||||
otOptions[FPSTR(S_DHW_BLOCKING)] = src.opentherm.options.dhwBlocking;
|
otOptions[FPSTR(S_DHW_BLOCKING)] = src.opentherm.options.dhwBlocking;
|
||||||
otOptions[FPSTR(S_MODULATION_SYNC_WITH_HEATING)] = src.opentherm.options.modulationSyncWithHeating;
|
otOptions[FPSTR(S_DHW_STATE_AS_DHW_BLOCKING)] = src.opentherm.options.dhwStateAsDhwBlocking;
|
||||||
otOptions[FPSTR(S_MAX_TEMP_SYNC_WITH_TARGET_TEMP)] = src.opentherm.options.maxTempSyncWithTargetTemp;
|
otOptions[FPSTR(S_MAX_TEMP_SYNC_WITH_TARGET_TEMP)] = src.opentherm.options.maxTempSyncWithTargetTemp;
|
||||||
otOptions[FPSTR(S_GET_MIN_MAX_TEMP)] = src.opentherm.options.getMinMaxTemp;
|
otOptions[FPSTR(S_GET_MIN_MAX_TEMP)] = src.opentherm.options.getMinMaxTemp;
|
||||||
|
otOptions[FPSTR(S_IGNORE_DIAG_STATE)] = src.opentherm.options.ignoreDiagState;
|
||||||
|
otOptions[FPSTR(S_AUTO_FAULT_RESET)] = src.opentherm.options.autoFaultReset;
|
||||||
|
otOptions[FPSTR(S_AUTO_DIAG_RESET)] = src.opentherm.options.autoDiagReset;
|
||||||
|
otOptions[FPSTR(S_SET_DATE_AND_TIME)] = src.opentherm.options.setDateAndTime;
|
||||||
otOptions[FPSTR(S_NATIVE_HEATING_CONTROL)] = src.opentherm.options.nativeHeatingControl;
|
otOptions[FPSTR(S_NATIVE_HEATING_CONTROL)] = src.opentherm.options.nativeHeatingControl;
|
||||||
otOptions[FPSTR(S_IMMERGAS_FIX)] = src.opentherm.options.immergasFix;
|
otOptions[FPSTR(S_IMMERGAS_FIX)] = src.opentherm.options.immergasFix;
|
||||||
|
|
||||||
@@ -491,12 +494,26 @@ void settingsToJson(const Settings& src, JsonVariant dst, bool safe = false) {
|
|||||||
heating[FPSTR(S_TURBO_FACTOR)] = roundf(src.heating.turboFactor, 3);
|
heating[FPSTR(S_TURBO_FACTOR)] = roundf(src.heating.turboFactor, 3);
|
||||||
heating[FPSTR(S_MIN_TEMP)] = src.heating.minTemp;
|
heating[FPSTR(S_MIN_TEMP)] = src.heating.minTemp;
|
||||||
heating[FPSTR(S_MAX_TEMP)] = src.heating.maxTemp;
|
heating[FPSTR(S_MAX_TEMP)] = src.heating.maxTemp;
|
||||||
|
heating[FPSTR(S_MAX_MODULATION)] = src.heating.maxModulation;
|
||||||
|
|
||||||
|
auto heatingOverheatProtection = heating[FPSTR(S_OVERHEAT_PROTECTION)].to<JsonObject>();
|
||||||
|
heatingOverheatProtection[FPSTR(S_HIGH_TEMP)] = src.heating.overheatProtection.highTemp;
|
||||||
|
heatingOverheatProtection[FPSTR(S_LOW_TEMP)] = src.heating.overheatProtection.lowTemp;
|
||||||
|
|
||||||
|
auto freezeProtection = heating[FPSTR(S_FREEZE_PROTECTION)].to<JsonObject>();
|
||||||
|
freezeProtection[FPSTR(S_LOW_TEMP)] = src.heating.freezeProtection.lowTemp;
|
||||||
|
freezeProtection[FPSTR(S_THRESHOLD_TIME)] = src.heating.freezeProtection.thresholdTime;
|
||||||
|
|
||||||
auto dhw = dst[FPSTR(S_DHW)].to<JsonObject>();
|
auto dhw = dst[FPSTR(S_DHW)].to<JsonObject>();
|
||||||
dhw[FPSTR(S_ENABLED)] = src.dhw.enabled;
|
dhw[FPSTR(S_ENABLED)] = src.dhw.enabled;
|
||||||
dhw[FPSTR(S_TARGET)] = roundf(src.dhw.target, 1);
|
dhw[FPSTR(S_TARGET)] = roundf(src.dhw.target, 1);
|
||||||
dhw[FPSTR(S_MIN_TEMP)] = src.dhw.minTemp;
|
dhw[FPSTR(S_MIN_TEMP)] = src.dhw.minTemp;
|
||||||
dhw[FPSTR(S_MAX_TEMP)] = src.dhw.maxTemp;
|
dhw[FPSTR(S_MAX_TEMP)] = src.dhw.maxTemp;
|
||||||
|
dhw[FPSTR(S_MAX_MODULATION)] = src.dhw.maxModulation;
|
||||||
|
|
||||||
|
auto dhwOverheatProtection = dhw[FPSTR(S_OVERHEAT_PROTECTION)].to<JsonObject>();
|
||||||
|
dhwOverheatProtection[FPSTR(S_HIGH_TEMP)] = src.dhw.overheatProtection.highTemp;
|
||||||
|
dhwOverheatProtection[FPSTR(S_LOW_TEMP)] = src.dhw.overheatProtection.lowTemp;
|
||||||
|
|
||||||
auto equitherm = dst[FPSTR(S_EQUITHERM)].to<JsonObject>();
|
auto equitherm = dst[FPSTR(S_EQUITHERM)].to<JsonObject>();
|
||||||
equitherm[FPSTR(S_ENABLED)] = src.equitherm.enabled;
|
equitherm[FPSTR(S_ENABLED)] = src.equitherm.enabled;
|
||||||
@@ -811,15 +828,6 @@ bool jsonToSettings(const JsonVariantConst src, Settings& dst, bool safe = false
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!src[FPSTR(S_OPENTHERM)][FPSTR(S_MAX_MODULATION)].isNull()) {
|
|
||||||
unsigned char value = src[FPSTR(S_OPENTHERM)][FPSTR(S_MAX_MODULATION)].as<unsigned char>();
|
|
||||||
|
|
||||||
if (value > 0 && value <= 100 && value != dst.opentherm.maxModulation) {
|
|
||||||
dst.opentherm.maxModulation = value;
|
|
||||||
changed = true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!src[FPSTR(S_OPENTHERM)][FPSTR(S_MIN_POWER)].isNull()) {
|
if (!src[FPSTR(S_OPENTHERM)][FPSTR(S_MIN_POWER)].isNull()) {
|
||||||
float value = src[FPSTR(S_OPENTHERM)][FPSTR(S_MIN_POWER)].as<float>();
|
float value = src[FPSTR(S_OPENTHERM)][FPSTR(S_MIN_POWER)].as<float>();
|
||||||
|
|
||||||
@@ -928,11 +936,11 @@ bool jsonToSettings(const JsonVariantConst src, Settings& dst, bool safe = false
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (src[FPSTR(S_OPENTHERM)][FPSTR(S_OPTIONS)][FPSTR(S_MODULATION_SYNC_WITH_HEATING)].is<bool>()) {
|
if (src[FPSTR(S_OPENTHERM)][FPSTR(S_OPTIONS)][FPSTR(S_DHW_STATE_AS_DHW_BLOCKING)].is<bool>()) {
|
||||||
bool value = src[FPSTR(S_OPENTHERM)][FPSTR(S_OPTIONS)][FPSTR(S_MODULATION_SYNC_WITH_HEATING)].as<bool>();
|
bool value = src[FPSTR(S_OPENTHERM)][FPSTR(S_OPTIONS)][FPSTR(S_DHW_STATE_AS_DHW_BLOCKING)].as<bool>();
|
||||||
|
|
||||||
if (value != dst.opentherm.options.modulationSyncWithHeating) {
|
if (value != dst.opentherm.options.dhwStateAsDhwBlocking) {
|
||||||
dst.opentherm.options.modulationSyncWithHeating = value;
|
dst.opentherm.options.dhwStateAsDhwBlocking = value;
|
||||||
changed = true;
|
changed = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -955,6 +963,42 @@ bool jsonToSettings(const JsonVariantConst src, Settings& dst, bool safe = false
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (src[FPSTR(S_OPENTHERM)][FPSTR(S_OPTIONS)][FPSTR(S_IGNORE_DIAG_STATE)].is<bool>()) {
|
||||||
|
bool value = src[FPSTR(S_OPENTHERM)][FPSTR(S_OPTIONS)][FPSTR(S_IGNORE_DIAG_STATE)].as<bool>();
|
||||||
|
|
||||||
|
if (value != dst.opentherm.options.ignoreDiagState) {
|
||||||
|
dst.opentherm.options.ignoreDiagState = value;
|
||||||
|
changed = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (src[FPSTR(S_OPENTHERM)][FPSTR(S_OPTIONS)][FPSTR(S_AUTO_FAULT_RESET)].is<bool>()) {
|
||||||
|
bool value = src[FPSTR(S_OPENTHERM)][FPSTR(S_OPTIONS)][FPSTR(S_AUTO_FAULT_RESET)].as<bool>();
|
||||||
|
|
||||||
|
if (value != dst.opentherm.options.autoFaultReset) {
|
||||||
|
dst.opentherm.options.autoFaultReset = value;
|
||||||
|
changed = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (src[FPSTR(S_OPENTHERM)][FPSTR(S_OPTIONS)][FPSTR(S_AUTO_DIAG_RESET)].is<bool>()) {
|
||||||
|
bool value = src[FPSTR(S_OPENTHERM)][FPSTR(S_OPTIONS)][FPSTR(S_AUTO_DIAG_RESET)].as<bool>();
|
||||||
|
|
||||||
|
if (value != dst.opentherm.options.autoDiagReset) {
|
||||||
|
dst.opentherm.options.autoDiagReset = value;
|
||||||
|
changed = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (src[FPSTR(S_OPENTHERM)][FPSTR(S_OPTIONS)][FPSTR(S_SET_DATE_AND_TIME)].is<bool>()) {
|
||||||
|
bool value = src[FPSTR(S_OPENTHERM)][FPSTR(S_OPTIONS)][FPSTR(S_SET_DATE_AND_TIME)].as<bool>();
|
||||||
|
|
||||||
|
if (value != dst.opentherm.options.setDateAndTime) {
|
||||||
|
dst.opentherm.options.setDateAndTime = value;
|
||||||
|
changed = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if (src[FPSTR(S_OPENTHERM)][FPSTR(S_OPTIONS)][FPSTR(S_NATIVE_HEATING_CONTROL)].is<bool>()) {
|
if (src[FPSTR(S_OPENTHERM)][FPSTR(S_OPTIONS)][FPSTR(S_NATIVE_HEATING_CONTROL)].is<bool>()) {
|
||||||
bool value = src[FPSTR(S_OPENTHERM)][FPSTR(S_OPTIONS)][FPSTR(S_NATIVE_HEATING_CONTROL)].as<bool>();
|
bool value = src[FPSTR(S_OPENTHERM)][FPSTR(S_OPTIONS)][FPSTR(S_NATIVE_HEATING_CONTROL)].as<bool>();
|
||||||
|
|
||||||
@@ -1280,7 +1324,7 @@ bool jsonToSettings(const JsonVariantConst src, Settings& dst, bool safe = false
|
|||||||
if (!src[FPSTR(S_HEATING)][FPSTR(S_MIN_TEMP)].isNull()) {
|
if (!src[FPSTR(S_HEATING)][FPSTR(S_MIN_TEMP)].isNull()) {
|
||||||
unsigned char value = src[FPSTR(S_HEATING)][FPSTR(S_MIN_TEMP)].as<unsigned char>();
|
unsigned char value = src[FPSTR(S_HEATING)][FPSTR(S_MIN_TEMP)].as<unsigned char>();
|
||||||
|
|
||||||
if (value != dst.heating.minTemp && value >= vars.slave.heating.minTemp && value < vars.slave.heating.maxTemp && value != dst.heating.minTemp) {
|
if (value != dst.heating.minTemp && value >= vars.slave.heating.minTemp && value < vars.slave.heating.maxTemp && value != dst.heating.maxTemp) {
|
||||||
dst.heating.minTemp = value;
|
dst.heating.minTemp = value;
|
||||||
changed = true;
|
changed = true;
|
||||||
}
|
}
|
||||||
@@ -1289,7 +1333,7 @@ bool jsonToSettings(const JsonVariantConst src, Settings& dst, bool safe = false
|
|||||||
if (!src[FPSTR(S_HEATING)][FPSTR(S_MAX_TEMP)].isNull()) {
|
if (!src[FPSTR(S_HEATING)][FPSTR(S_MAX_TEMP)].isNull()) {
|
||||||
unsigned char value = src[FPSTR(S_HEATING)][FPSTR(S_MAX_TEMP)].as<unsigned char>();
|
unsigned char value = src[FPSTR(S_HEATING)][FPSTR(S_MAX_TEMP)].as<unsigned char>();
|
||||||
|
|
||||||
if (value != dst.heating.maxTemp && value > vars.slave.heating.minTemp && value <= vars.slave.heating.maxTemp && value != dst.heating.maxTemp) {
|
if (value != dst.heating.maxTemp && value > vars.slave.heating.minTemp && value <= vars.slave.heating.maxTemp && value != dst.heating.minTemp) {
|
||||||
dst.heating.maxTemp = value;
|
dst.heating.maxTemp = value;
|
||||||
changed = true;
|
changed = true;
|
||||||
}
|
}
|
||||||
@@ -1301,6 +1345,59 @@ bool jsonToSettings(const JsonVariantConst src, Settings& dst, bool safe = false
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
if (!src[FPSTR(S_HEATING)][FPSTR(S_MAX_MODULATION)].isNull()) {
|
||||||
|
unsigned char value = src[FPSTR(S_HEATING)][FPSTR(S_MAX_MODULATION)].as<unsigned char>();
|
||||||
|
|
||||||
|
if (value > 0 && value <= 100 && value != dst.heating.maxModulation) {
|
||||||
|
dst.heating.maxModulation = value;
|
||||||
|
changed = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!src[FPSTR(S_HEATING)][FPSTR(S_OVERHEAT_PROTECTION)][FPSTR(S_HIGH_TEMP)].isNull()) {
|
||||||
|
unsigned char value = src[FPSTR(S_HEATING)][FPSTR(S_OVERHEAT_PROTECTION)][FPSTR(S_HIGH_TEMP)].as<unsigned char>();
|
||||||
|
|
||||||
|
if (isValidTemp(value, dst.system.unitSystem, 0.0f, 100.0f) && value != dst.heating.overheatProtection.highTemp) {
|
||||||
|
dst.heating.overheatProtection.highTemp = value;
|
||||||
|
changed = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!src[FPSTR(S_HEATING)][FPSTR(S_OVERHEAT_PROTECTION)][FPSTR(S_LOW_TEMP)].isNull()) {
|
||||||
|
unsigned char value = src[FPSTR(S_HEATING)][FPSTR(S_OVERHEAT_PROTECTION)][FPSTR(S_LOW_TEMP)].as<unsigned char>();
|
||||||
|
|
||||||
|
if (isValidTemp(value, dst.system.unitSystem, 0.0f, 99.0f) && value != dst.heating.overheatProtection.lowTemp) {
|
||||||
|
dst.heating.overheatProtection.lowTemp = value;
|
||||||
|
changed = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (dst.heating.overheatProtection.highTemp < dst.heating.overheatProtection.lowTemp) {
|
||||||
|
dst.heating.overheatProtection.highTemp = dst.heating.overheatProtection.lowTemp;
|
||||||
|
changed = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!src[FPSTR(S_HEATING)][FPSTR(S_FREEZE_PROTECTION)][FPSTR(S_LOW_TEMP)].isNull()) {
|
||||||
|
unsigned short value = src[FPSTR(S_HEATING)][FPSTR(S_FREEZE_PROTECTION)][FPSTR(S_LOW_TEMP)].as<uint8_t>();
|
||||||
|
|
||||||
|
if (isValidTemp(value, dst.system.unitSystem, 1, 30) && value != dst.heating.freezeProtection.lowTemp) {
|
||||||
|
dst.heating.freezeProtection.lowTemp = value;
|
||||||
|
changed = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!src[FPSTR(S_HEATING)][FPSTR(S_FREEZE_PROTECTION)][FPSTR(S_THRESHOLD_TIME)].isNull()) {
|
||||||
|
unsigned short value = src[FPSTR(S_HEATING)][FPSTR(S_FREEZE_PROTECTION)][FPSTR(S_THRESHOLD_TIME)].as<unsigned short>();
|
||||||
|
|
||||||
|
if (value >= 30 && value <= 1800) {
|
||||||
|
if (value != dst.heating.freezeProtection.thresholdTime) {
|
||||||
|
dst.heating.freezeProtection.thresholdTime = value;
|
||||||
|
changed = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
// dhw
|
// dhw
|
||||||
if (src[FPSTR(S_DHW)][FPSTR(S_ENABLED)].is<bool>()) {
|
if (src[FPSTR(S_DHW)][FPSTR(S_ENABLED)].is<bool>()) {
|
||||||
bool value = src[FPSTR(S_DHW)][FPSTR(S_ENABLED)].as<bool>();
|
bool value = src[FPSTR(S_DHW)][FPSTR(S_ENABLED)].as<bool>();
|
||||||
@@ -1334,6 +1431,38 @@ bool jsonToSettings(const JsonVariantConst src, Settings& dst, bool safe = false
|
|||||||
changed = true;
|
changed = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (!src[FPSTR(S_DHW)][FPSTR(S_MAX_MODULATION)].isNull()) {
|
||||||
|
unsigned char value = src[FPSTR(S_DHW)][FPSTR(S_MAX_MODULATION)].as<unsigned char>();
|
||||||
|
|
||||||
|
if (value > 0 && value <= 100 && value != dst.dhw.maxModulation) {
|
||||||
|
dst.dhw.maxModulation = value;
|
||||||
|
changed = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!src[FPSTR(S_DHW)][FPSTR(S_OVERHEAT_PROTECTION)][FPSTR(S_HIGH_TEMP)].isNull()) {
|
||||||
|
unsigned char value = src[FPSTR(S_DHW)][FPSTR(S_OVERHEAT_PROTECTION)][FPSTR(S_HIGH_TEMP)].as<unsigned char>();
|
||||||
|
|
||||||
|
if (isValidTemp(value, dst.system.unitSystem, 0.0f, 100.0f) && value != dst.dhw.overheatProtection.highTemp) {
|
||||||
|
dst.dhw.overheatProtection.highTemp = value;
|
||||||
|
changed = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!src[FPSTR(S_DHW)][FPSTR(S_OVERHEAT_PROTECTION)][FPSTR(S_LOW_TEMP)].isNull()) {
|
||||||
|
unsigned char value = src[FPSTR(S_DHW)][FPSTR(S_OVERHEAT_PROTECTION)][FPSTR(S_LOW_TEMP)].as<unsigned char>();
|
||||||
|
|
||||||
|
if (isValidTemp(value, dst.system.unitSystem, 0.0f, 99.0f) && value != dst.dhw.overheatProtection.lowTemp) {
|
||||||
|
dst.dhw.overheatProtection.lowTemp = value;
|
||||||
|
changed = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (dst.dhw.overheatProtection.highTemp < dst.dhw.overheatProtection.lowTemp) {
|
||||||
|
dst.dhw.overheatProtection.highTemp = dst.dhw.overheatProtection.lowTemp;
|
||||||
|
changed = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
if (!safe) {
|
if (!safe) {
|
||||||
// external pump
|
// external pump
|
||||||
@@ -1692,6 +1821,7 @@ bool jsonToSensorSettings(const uint8_t sensorId, const JsonVariantConst src, Se
|
|||||||
case static_cast<uint8_t>(Sensors::Purpose::EXHAUST_TEMP):
|
case static_cast<uint8_t>(Sensors::Purpose::EXHAUST_TEMP):
|
||||||
case static_cast<uint8_t>(Sensors::Purpose::MODULATION_LEVEL):
|
case static_cast<uint8_t>(Sensors::Purpose::MODULATION_LEVEL):
|
||||||
|
|
||||||
|
case static_cast<uint8_t>(Sensors::Purpose::NUMBER):
|
||||||
case static_cast<uint8_t>(Sensors::Purpose::POWER_FACTOR):
|
case static_cast<uint8_t>(Sensors::Purpose::POWER_FACTOR):
|
||||||
case static_cast<uint8_t>(Sensors::Purpose::POWER):
|
case static_cast<uint8_t>(Sensors::Purpose::POWER):
|
||||||
case static_cast<uint8_t>(Sensors::Purpose::FAN_SPEED):
|
case static_cast<uint8_t>(Sensors::Purpose::FAN_SPEED):
|
||||||
@@ -1736,6 +1866,15 @@ bool jsonToSensorSettings(const uint8_t sensorId, const JsonVariantConst src, Se
|
|||||||
case static_cast<uint8_t>(Sensors::Type::OT_FAN_SPEED_SETPOINT):
|
case static_cast<uint8_t>(Sensors::Type::OT_FAN_SPEED_SETPOINT):
|
||||||
case static_cast<uint8_t>(Sensors::Type::OT_FAN_SPEED_CURRENT):
|
case static_cast<uint8_t>(Sensors::Type::OT_FAN_SPEED_CURRENT):
|
||||||
|
|
||||||
|
case static_cast<uint8_t>(Sensors::Type::OT_BURNER_STARTS):
|
||||||
|
case static_cast<uint8_t>(Sensors::Type::OT_DHW_BURNER_STARTS):
|
||||||
|
case static_cast<uint8_t>(Sensors::Type::OT_HEATING_PUMP_STARTS):
|
||||||
|
case static_cast<uint8_t>(Sensors::Type::OT_DHW_PUMP_STARTS):
|
||||||
|
case static_cast<uint8_t>(Sensors::Type::OT_BURNER_HOURS):
|
||||||
|
case static_cast<uint8_t>(Sensors::Type::OT_DHW_BURNER_HOURS):
|
||||||
|
case static_cast<uint8_t>(Sensors::Type::OT_HEATING_PUMP_HOURS):
|
||||||
|
case static_cast<uint8_t>(Sensors::Type::OT_DHW_PUMP_HOURS):
|
||||||
|
|
||||||
case static_cast<uint8_t>(Sensors::Type::NTC_10K_TEMP):
|
case static_cast<uint8_t>(Sensors::Type::NTC_10K_TEMP):
|
||||||
case static_cast<uint8_t>(Sensors::Type::DALLAS_TEMP):
|
case static_cast<uint8_t>(Sensors::Type::DALLAS_TEMP):
|
||||||
case static_cast<uint8_t>(Sensors::Type::BLUETOOTH):
|
case static_cast<uint8_t>(Sensors::Type::BLUETOOTH):
|
||||||
@@ -1755,7 +1894,7 @@ bool jsonToSensorSettings(const uint8_t sensorId, const JsonVariantConst src, Se
|
|||||||
|
|
||||||
// gpio
|
// gpio
|
||||||
if (!src[FPSTR(S_GPIO)].isNull()) {
|
if (!src[FPSTR(S_GPIO)].isNull()) {
|
||||||
if (dst.type != Sensors::Type::DALLAS_TEMP && dst.type == Sensors::Type::BLUETOOTH && dst.type == Sensors::Type::NTC_10K_TEMP) {
|
if (dst.type != Sensors::Type::DALLAS_TEMP && dst.type != Sensors::Type::NTC_10K_TEMP) {
|
||||||
if (dst.gpio != GPIO_IS_NOT_CONFIGURED) {
|
if (dst.gpio != GPIO_IS_NOT_CONFIGURED) {
|
||||||
dst.gpio = GPIO_IS_NOT_CONFIGURED;
|
dst.gpio = GPIO_IS_NOT_CONFIGURED;
|
||||||
changed = true;
|
changed = true;
|
||||||
@@ -1955,6 +2094,7 @@ void varsToJson(const Variables& src, JsonVariant dst) {
|
|||||||
mHeating[FPSTR(S_ENABLED)] = src.master.heating.enabled;
|
mHeating[FPSTR(S_ENABLED)] = src.master.heating.enabled;
|
||||||
mHeating[FPSTR(S_BLOCKING)] = src.master.heating.blocking;
|
mHeating[FPSTR(S_BLOCKING)] = src.master.heating.blocking;
|
||||||
mHeating[FPSTR(S_INDOOR_TEMP_CONTROL)] = src.master.heating.indoorTempControl;
|
mHeating[FPSTR(S_INDOOR_TEMP_CONTROL)] = src.master.heating.indoorTempControl;
|
||||||
|
mHeating[FPSTR(S_OVERHEAT)] = src.master.heating.overheat;
|
||||||
mHeating[FPSTR(S_SETPOINT_TEMP)] = roundf(src.master.heating.setpointTemp, 2);
|
mHeating[FPSTR(S_SETPOINT_TEMP)] = roundf(src.master.heating.setpointTemp, 2);
|
||||||
mHeating[FPSTR(S_TARGET_TEMP)] = roundf(src.master.heating.targetTemp, 2);
|
mHeating[FPSTR(S_TARGET_TEMP)] = roundf(src.master.heating.targetTemp, 2);
|
||||||
mHeating[FPSTR(S_CURRENT_TEMP)] = roundf(src.master.heating.currentTemp, 2);
|
mHeating[FPSTR(S_CURRENT_TEMP)] = roundf(src.master.heating.currentTemp, 2);
|
||||||
@@ -1966,6 +2106,7 @@ void varsToJson(const Variables& src, JsonVariant dst) {
|
|||||||
|
|
||||||
auto mDhw = master[FPSTR(S_DHW)].to<JsonObject>();
|
auto mDhw = master[FPSTR(S_DHW)].to<JsonObject>();
|
||||||
mDhw[FPSTR(S_ENABLED)] = src.master.dhw.enabled;
|
mDhw[FPSTR(S_ENABLED)] = src.master.dhw.enabled;
|
||||||
|
mDhw[FPSTR(S_OVERHEAT)] = src.master.dhw.overheat;
|
||||||
mDhw[FPSTR(S_TARGET_TEMP)] = roundf(src.master.dhw.targetTemp, 2);
|
mDhw[FPSTR(S_TARGET_TEMP)] = roundf(src.master.dhw.targetTemp, 2);
|
||||||
mDhw[FPSTR(S_CURRENT_TEMP)] = roundf(src.master.dhw.currentTemp, 2);
|
mDhw[FPSTR(S_CURRENT_TEMP)] = roundf(src.master.dhw.currentTemp, 2);
|
||||||
mDhw[FPSTR(S_RETURN_TEMP)] = roundf(src.master.dhw.returnTemp, 2);
|
mDhw[FPSTR(S_RETURN_TEMP)] = roundf(src.master.dhw.returnTemp, 2);
|
||||||
|
|||||||
507
src_data/locales/cn.json
Normal file
507
src_data/locales/cn.json
Normal file
@@ -0,0 +1,507 @@
|
|||||||
|
{
|
||||||
|
"values": {
|
||||||
|
"logo": "OpenTherm Gateway",
|
||||||
|
"nav": {
|
||||||
|
"license": "授权许可",
|
||||||
|
"source": "源代码",
|
||||||
|
"help": "帮助",
|
||||||
|
"issues": "问题与反馈",
|
||||||
|
"releases": "发行版"
|
||||||
|
},
|
||||||
|
"dbm": "dBm",
|
||||||
|
"kw": "kW",
|
||||||
|
"time": {
|
||||||
|
"days": "天",
|
||||||
|
"hours": "小时",
|
||||||
|
"min": "分",
|
||||||
|
"sec": "秒"
|
||||||
|
},
|
||||||
|
|
||||||
|
"button": {
|
||||||
|
"upgrade": "固件升级",
|
||||||
|
"restart": "重启",
|
||||||
|
"save": "保存",
|
||||||
|
"saved": "已保存",
|
||||||
|
"refresh": "刷新",
|
||||||
|
"restore": "恢复",
|
||||||
|
"restored": "已恢复",
|
||||||
|
"backup": "备份",
|
||||||
|
"wait": "请等待...",
|
||||||
|
"uploading": "上传中...",
|
||||||
|
"success": "成功",
|
||||||
|
"error": "错误"
|
||||||
|
},
|
||||||
|
|
||||||
|
"index": {
|
||||||
|
"title": "OpenTherm Gateway",
|
||||||
|
|
||||||
|
"section": {
|
||||||
|
"network": "网络",
|
||||||
|
"system": "系统"
|
||||||
|
},
|
||||||
|
|
||||||
|
"system": {
|
||||||
|
"build": {
|
||||||
|
"title": "Build",
|
||||||
|
"version": "固件版本",
|
||||||
|
"date": "日期",
|
||||||
|
"core": "内核版本",
|
||||||
|
"sdk": "SDK"
|
||||||
|
},
|
||||||
|
"uptime": "运行时间",
|
||||||
|
"memory": {
|
||||||
|
"title": "可用内存",
|
||||||
|
"maxFreeBlock": "max free block",
|
||||||
|
"min": "min"
|
||||||
|
},
|
||||||
|
"board": "开发板",
|
||||||
|
"chip": {
|
||||||
|
"model": "芯片",
|
||||||
|
"cores": "核心数",
|
||||||
|
"freq": "频率"
|
||||||
|
},
|
||||||
|
"flash": {
|
||||||
|
"size": "闪存容量",
|
||||||
|
"realSize": "实际容量"
|
||||||
|
},
|
||||||
|
"lastResetReason": "上次重置原因"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
|
||||||
|
"dashboard": {
|
||||||
|
"name": "仪表盘",
|
||||||
|
"title": "仪表盘 - OpenTherm Gateway",
|
||||||
|
|
||||||
|
"section": {
|
||||||
|
"control": "调节",
|
||||||
|
"states": "状态",
|
||||||
|
"sensors": "传感器",
|
||||||
|
"diag": "OpenTherm 诊断"
|
||||||
|
},
|
||||||
|
|
||||||
|
"thermostat": {
|
||||||
|
"heating": "供暖",
|
||||||
|
"dhw": "生活热水",
|
||||||
|
"temp.current": "当前温度",
|
||||||
|
"enable": "启用",
|
||||||
|
"turbo": "Turbo 模式"
|
||||||
|
},
|
||||||
|
|
||||||
|
"notify": {
|
||||||
|
"fault": {
|
||||||
|
"title": "锅炉报警状态已激活!",
|
||||||
|
"note": "建议检查锅炉并查看说明书对应的报警代码:"
|
||||||
|
},
|
||||||
|
"diag": {
|
||||||
|
"title": "锅炉诊断状态已激活!",
|
||||||
|
"note": "锅炉可能需要检查,建议查看说明书对应的诊断代码:"
|
||||||
|
},
|
||||||
|
"reset": "点击复位"
|
||||||
|
},
|
||||||
|
|
||||||
|
"states": {
|
||||||
|
"mNetworkConnected": "网络连接状态",
|
||||||
|
"mMqttConnected": "MQTT服务器连接状态",
|
||||||
|
"mEmergencyState": "应急模式",
|
||||||
|
"mExtPumpState": "外置循环泵",
|
||||||
|
"mCascadeControlInput": "Cascade 控制 (input)",
|
||||||
|
"mCascadeControlOutput": "Cascade 控制 (output)",
|
||||||
|
|
||||||
|
"sConnected": "OpenTherm 通讯状态",
|
||||||
|
"sFlame": "火焰",
|
||||||
|
"sCooling": "制冷",
|
||||||
|
"sFaultActive": "报警状态",
|
||||||
|
"sFaultCode": "报警代码",
|
||||||
|
"sDiagActive": "诊断状态",
|
||||||
|
"sDiagCode": "诊断代码",
|
||||||
|
|
||||||
|
"mHeatEnabled": "供暖功能已启用",
|
||||||
|
"mHeatBlocking": "供暖",
|
||||||
|
"mHeatOverheat": "供暖超热保护",
|
||||||
|
"sHeatActive": "供暖激活状态",
|
||||||
|
"mHeatSetpointTemp": "供暖供水设定温度",
|
||||||
|
"mHeatTargetTemp": "供暖供水目标温度",
|
||||||
|
"mHeatCurrTemp": "供暖当前供水温度",
|
||||||
|
"mHeatRetTemp": "供暖回水温度",
|
||||||
|
"mHeatIndoorTemp": "供暖,室内温度",
|
||||||
|
"mHeatOutdoorTemp": "供暖,室外温度",
|
||||||
|
|
||||||
|
"mDhwEnabled": "生活热水功能已启用",
|
||||||
|
"mDhwOverheat": "生活热水超热保护",
|
||||||
|
"sDhwActive": "生活热水激活",
|
||||||
|
"mDhwTargetTemp": "生活热水目标温度",
|
||||||
|
"mDhwCurrTemp": "生活热水当前出水温度",
|
||||||
|
"mDhwRetTemp": "生活热水回水温度"
|
||||||
|
},
|
||||||
|
|
||||||
|
"sensors": {
|
||||||
|
"values": {
|
||||||
|
"temp": "温度",
|
||||||
|
"humidity": "湿度",
|
||||||
|
"battery": "电量",
|
||||||
|
"rssi": "RSSI"
|
||||||
|
}
|
||||||
|
}
|
||||||
|
},
|
||||||
|
|
||||||
|
"network": {
|
||||||
|
"title": "网络 - OpenTherm Gateway",
|
||||||
|
"name": "网络设置",
|
||||||
|
|
||||||
|
"section": {
|
||||||
|
"static": "静态设置",
|
||||||
|
"availableNetworks": "可用网络",
|
||||||
|
"staSettings": "WiFi 设置",
|
||||||
|
"apSettings": "AP 设置"
|
||||||
|
},
|
||||||
|
|
||||||
|
"scan": {
|
||||||
|
"pos": "#",
|
||||||
|
"info": "Info"
|
||||||
|
},
|
||||||
|
|
||||||
|
"wifi": {
|
||||||
|
"ssid": "SSID",
|
||||||
|
"password": "密码",
|
||||||
|
"channel": "频道",
|
||||||
|
"signal": "信号强度",
|
||||||
|
"connected": "已连接"
|
||||||
|
},
|
||||||
|
|
||||||
|
"params": {
|
||||||
|
"hostname": "Hostname",
|
||||||
|
"dhcp": "自动 (DHCP)",
|
||||||
|
"mac": "物理地址 (MAC)",
|
||||||
|
"ip": "IP",
|
||||||
|
"subnet": "子网掩码",
|
||||||
|
"gateway": "网关",
|
||||||
|
"dns": "DNS 服务器"
|
||||||
|
},
|
||||||
|
|
||||||
|
"sta": {
|
||||||
|
"channel.note": "自动选择设置为0"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
|
||||||
|
"sensors": {
|
||||||
|
"title": "传感器设置 - OpenTherm Gateway",
|
||||||
|
"name": "传感器设置",
|
||||||
|
|
||||||
|
"enabled": "启用",
|
||||||
|
"sensorName": {
|
||||||
|
"title": "传感器名称",
|
||||||
|
"note": "只能包含:a-z、A-Z、0-9、下划线和空格"
|
||||||
|
},
|
||||||
|
"purpose": "用途",
|
||||||
|
"purposes": {
|
||||||
|
"outdoorTemp": "室外温度",
|
||||||
|
"indoorTemp": "室内温度",
|
||||||
|
"heatTemp": "供暖,温度",
|
||||||
|
"heatRetTemp": "供暖回水温度",
|
||||||
|
"dhwTemp": "生活热水温度",
|
||||||
|
"dhwRetTemp": "生活热水回水温度",
|
||||||
|
"dhwFlowRate": "生活热水水流量",
|
||||||
|
"exhaustTemp": "烟气温度",
|
||||||
|
"modLevel": "Modulation level (%)",
|
||||||
|
"number": "Number (raw)",
|
||||||
|
"powerFactor": "功率 (%)",
|
||||||
|
"power": "功率(kW)",
|
||||||
|
"fanSpeed": "风机转速",
|
||||||
|
"co2": "CO2",
|
||||||
|
"pressure": "压力",
|
||||||
|
"humidity": "湿度",
|
||||||
|
"temperature": "温度",
|
||||||
|
"notConfigured": "未配置"
|
||||||
|
},
|
||||||
|
"type": "类型/来源",
|
||||||
|
"types": {
|
||||||
|
"otOutdoorTemp": "OpenTherm, outdoor temp",
|
||||||
|
"otHeatTemp": "OpenTherm, heating, temp",
|
||||||
|
"otHeatRetTemp": "OpenTherm, heating, return temp",
|
||||||
|
"otDhwTemp": "OpenTherm, DHW, temperature",
|
||||||
|
"otDhwTemp2": "OpenTherm, DHW, temperature 2",
|
||||||
|
"otDhwFlowRate": "OpenTherm, DHW, flow rate",
|
||||||
|
"otCh2Temp": "OpenTherm, channel 2, temp",
|
||||||
|
"otExhaustTemp": "OpenTherm, exhaust temp",
|
||||||
|
"otHeatExchangerTemp": "OpenTherm, heat exchanger temp",
|
||||||
|
"otPressure": "OpenTherm, pressure",
|
||||||
|
"otModLevel": "OpenTherm, modulation level",
|
||||||
|
"otCurrentPower": "OpenTherm, current power",
|
||||||
|
"otExhaustCo2": "OpenTherm, exhaust CO2",
|
||||||
|
"otExhaustFanSpeed": "OpenTherm, exhaust fan speed",
|
||||||
|
"otSupplyFanSpeed": "OpenTherm, supply fan speed",
|
||||||
|
"otSolarStorageTemp": "OpenTherm, solar storage temp",
|
||||||
|
"otSolarCollectorTemp": "OpenTherm, solar collector temp",
|
||||||
|
"otFanSpeedSetpoint": "OpenTherm, setpoint fan speed",
|
||||||
|
"otFanSpeedCurrent": "OpenTherm, current fan speed",
|
||||||
|
"otBurnerStarts": "OpenTherm, number of burner starts",
|
||||||
|
"otDhwBurnerStarts": "OpenTherm, number of burner starts (DHW)",
|
||||||
|
"otHeatingPumpStarts": "OpenTherm, number of pump starts (heating)",
|
||||||
|
"otDhwPumpStarts": "OpenTherm, number of pump starts (DHW)",
|
||||||
|
"otBurnerHours": "OpenTherm, number of burner operating hours",
|
||||||
|
"otDhwBurnerHours": "OpenTherm, number of burner operating hours (DHW)",
|
||||||
|
"otHeatingPumpHours": "OpenTherm, number of pump operating hours (heating)",
|
||||||
|
"otDhwPumpHours": "OpenTherm, number of pump operating hours (DHW)",
|
||||||
|
|
||||||
|
"ntcTemp": "NTC 传感器",
|
||||||
|
"dallasTemp": "DALLAS 传感器",
|
||||||
|
"bluetooth": "BLE 传感器",
|
||||||
|
"heatSetpointTemp": "Heating, setpoint temp",
|
||||||
|
"manual": "通过 MQTT/API 手动配置",
|
||||||
|
"notConfigured": "未配置"
|
||||||
|
},
|
||||||
|
"gpio": "GPIO",
|
||||||
|
"address": {
|
||||||
|
"title": "传感器地址",
|
||||||
|
"note": "如需自动检测DALLAS传感器,请保持默认设置;如需连接BLE设备,则需提供MAC地址"
|
||||||
|
},
|
||||||
|
"correction": {
|
||||||
|
"desc": "数值校正",
|
||||||
|
"offset": "补偿值(偏移量)",
|
||||||
|
"factor": "Multiplier"
|
||||||
|
},
|
||||||
|
"filtering": {
|
||||||
|
"desc": "数值滤波",
|
||||||
|
"enabled": {
|
||||||
|
"title": "启用滤波",
|
||||||
|
"note": "如果图表中有大量尖锐的噪声,此功能会很有用。使用的滤波器是 \"滑动平均滤波器\"."
|
||||||
|
},
|
||||||
|
"factor": {
|
||||||
|
"title": "滤波系数",
|
||||||
|
"note": "数值越低,数值变化越平滑且响应越滞后"
|
||||||
|
}
|
||||||
|
}
|
||||||
|
},
|
||||||
|
|
||||||
|
"settings": {
|
||||||
|
"title": "设置 - OpenTherm Gateway",
|
||||||
|
"name": "设置",
|
||||||
|
|
||||||
|
"section": {
|
||||||
|
"portal": "Portal 设置",
|
||||||
|
"system": "系统设置",
|
||||||
|
"diag": "诊断",
|
||||||
|
"heating": "供热设置",
|
||||||
|
"dhw": "生活热水设置",
|
||||||
|
"emergency": "应急模式设置",
|
||||||
|
"equitherm": "气候补偿设置",
|
||||||
|
"pid": "PID 参数设置",
|
||||||
|
"ot": "OpenTherm协议设置",
|
||||||
|
"mqtt": "MQTT 服务器设置",
|
||||||
|
"extPump": "外置循环泵设置",
|
||||||
|
"cascadeControl": "Cascade 级联控制设置"
|
||||||
|
},
|
||||||
|
|
||||||
|
"enable": "启用",
|
||||||
|
"note": {
|
||||||
|
"restart": "更改这些设置后,必须重启设备以使变更生效",
|
||||||
|
"blankNotUse": "空白 - 未使用",
|
||||||
|
"bleDevice": "BLE设备仅支持搭载BLE功能的特定ESP32开发板使用!"
|
||||||
|
},
|
||||||
|
|
||||||
|
"temp": {
|
||||||
|
"min": "最低温度",
|
||||||
|
"max": "最高温度"
|
||||||
|
},
|
||||||
|
"maxModulation": "最大调制范围",
|
||||||
|
"ohProtection": {
|
||||||
|
"title": "超温保护",
|
||||||
|
"desc": "<b>注意:</b> 当锅炉内置过热保护失效或工作异常导致系统超温时,此功能可提供额外保护。如需禁用,请将<b>最高温度</b>和<b>最低温度</b>均设为0。",
|
||||||
|
"highTemp": {
|
||||||
|
"title": "高温阈值",
|
||||||
|
"note": "触发燃烧器强制关闭的阈值温度"
|
||||||
|
},
|
||||||
|
"lowTemp": {
|
||||||
|
"title": "低温阈值",
|
||||||
|
"note": "燃烧器重新启动的阈值温度"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"freezeProtection": {
|
||||||
|
"title": "防冻保护",
|
||||||
|
"desc": "当热媒或室内温度在<b>等待时间</b> 内降至<b>低温阈值</b>以下时,系统将强制启动加热功能。",
|
||||||
|
"lowTemp": "低温阈值",
|
||||||
|
"thresholdTime": "等待时间<small>(秒)</small>"
|
||||||
|
},
|
||||||
|
|
||||||
|
"portal": {
|
||||||
|
"login": "登录",
|
||||||
|
"password": "密码",
|
||||||
|
"auth": "需身份验证",
|
||||||
|
"mdns": "使用 mDNS"
|
||||||
|
},
|
||||||
|
|
||||||
|
"system": {
|
||||||
|
"unit": "单位",
|
||||||
|
"metric": "公制 <small>(摄氏度、升、巴)</small>",
|
||||||
|
"imperial": "英制 <small>(华氏度、加仑、psi)</small>",
|
||||||
|
"statusLedGpio": "状态指示灯GPIO引脚",
|
||||||
|
"logLevel": "日志级别",
|
||||||
|
"serial": {
|
||||||
|
"enable": "启用串口",
|
||||||
|
"baud": "串口波特率"
|
||||||
|
},
|
||||||
|
"telnet": {
|
||||||
|
"enable": "启用 Telnet",
|
||||||
|
"port": {
|
||||||
|
"title": "Telnet 端口",
|
||||||
|
"note": "默认值:23"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"ntp": {
|
||||||
|
"server": "NTP服务器",
|
||||||
|
"timezone": "时区",
|
||||||
|
"timezonePresets": "选择预设配置..."
|
||||||
|
}
|
||||||
|
},
|
||||||
|
|
||||||
|
"heating": {
|
||||||
|
"hyst": "滞后值<small>(单位:度)</small>",
|
||||||
|
"turboFactor": "Turbo 模式系数"
|
||||||
|
},
|
||||||
|
|
||||||
|
"emergency": {
|
||||||
|
"desc": "紧急模式会在以下情况自动激活(当PID或气候补偿无法计算热媒设定值时):<br />启用气候补偿但室外温度传感器断开连接;<br />启用PID或 OpenTherm 选项中启用<i>原生供暖控制</i>但室内温度传感器断开连接。<br /><b>注意:</b> 网络故障或MQTT 服务器连接故障时,类型为<i>通过MQTT/API手动控制<i>的传感器将显示为断开连接状态。",
|
||||||
|
|
||||||
|
"target": {
|
||||||
|
"title": "目标温度",
|
||||||
|
"note": "<b>重要提示:</b> 若启用OpenTherm选项 <i>«原生供暖控制»</i>,此处设定值为<u>目标室内温度</u>;<br />其他所有情况下,此处设定值为 <u>目标热媒出水温度</u>."
|
||||||
|
},
|
||||||
|
"treshold": "阈值时间 <small>(秒)</small>"
|
||||||
|
},
|
||||||
|
|
||||||
|
"equitherm": {
|
||||||
|
"n": "N 系数",
|
||||||
|
"k": "K 系数",
|
||||||
|
"t": {
|
||||||
|
"title": "T 系数",
|
||||||
|
"note": "启用PID时此参数无效"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
|
||||||
|
"pid": {
|
||||||
|
"p": "P 系数",
|
||||||
|
"i": "I 系数",
|
||||||
|
"d": "D 系数",
|
||||||
|
"dt": "DT <small>以秒为单位</small>",
|
||||||
|
"limits": {
|
||||||
|
"title": "Limits",
|
||||||
|
"note": "<b>重要提示:</b> When using «Equitherm» and «PID» at the same time, the min and max temperatures limit the influence on the «Equitherm» result temperature.<br />Thus, if the min temperature is set to -15 and the max temperature is set to 15, then the final heat carrier setpoint will be from <code>equitherm_result - 15</code> to <code>equitherm_result + 15</code>."
|
||||||
|
},
|
||||||
|
"deadband": {
|
||||||
|
"title": "Deadband",
|
||||||
|
"note": "Deadband is a range around the target temperature where PID regulation becomes less active. Within this range, the algorithm can reduce intensity or pause adjustments to avoid overreacting to small fluctuations.<br /><br />For instance, with a target temperature of 22°, a lower threshold of 1.0, and an upper threshold of 0.5, the deadband operates between 21° and 22.5°. If the I coefficient is 0.0005 and the I multiplier is 0.05, then within the deadband, the I coefficient becomes: <code>0.0005 * 0.05 = 0.000025</code>",
|
||||||
|
"p_multiplier": "Multiplier for P factor",
|
||||||
|
"i_multiplier": "Multiplier for I factor",
|
||||||
|
"d_multiplier": "Multiplier for D factor",
|
||||||
|
"thresholdHigh": "Threshold high",
|
||||||
|
"thresholdLow": "Threshold low"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
|
||||||
|
"ot": {
|
||||||
|
"advanced": "高级设置",
|
||||||
|
"inGpio": "In GPIO",
|
||||||
|
"outGpio": "Out GPIO",
|
||||||
|
"ledGpio": "RX LED GPIO",
|
||||||
|
"memberId": "主设备成员 ID",
|
||||||
|
"flags": "主设备标志",
|
||||||
|
"minPower": {
|
||||||
|
"title": "最小锅炉功率 <small>(kW)</small>",
|
||||||
|
"note": "该值对应锅炉0-1%的调制水平,通常在锅炉参数设置中的\"最小有效热输出\"。"
|
||||||
|
},
|
||||||
|
"maxPower": {
|
||||||
|
"title": "最大锅炉功率 <small>(kW)</small>",
|
||||||
|
"note": "<b>0</b> - 自动检测,通常在锅炉参数设置中的\"最大有效热输出\"。 "
|
||||||
|
},
|
||||||
|
|
||||||
|
"options": {
|
||||||
|
"title": "选项(附加设置)",
|
||||||
|
"desc": "附加设置选项可调整锅炉的运行逻辑。由于协议未完整记录所有选项,同一选项在不同锅炉上可能产生不同效果。<br /><b>注意:</b>若系统运行正常,无需修改设置。",
|
||||||
|
"dhwSupport": "生活热水支持",
|
||||||
|
"coolingSupport": "制冷支持",
|
||||||
|
"summerWinterMode": "夏季/冬季模式",
|
||||||
|
"heatingStateToSummerWinterMode": "以供暖状态作为夏季/冬季模式",
|
||||||
|
"ch2AlwaysEnabled": "CH2 始终启用",
|
||||||
|
"heatingToCh2": "将供暖同步至 CH2",
|
||||||
|
"dhwToCh2": "将生活热水同步至 CH2",
|
||||||
|
"dhwBlocking": "生活热水锁定",
|
||||||
|
"dhwStateAsDhwBlocking": "以生活热水状态作为生活热水锁定依据",
|
||||||
|
"maxTempSyncWithTargetTemp": "将最高供暖温度与目标温度同步",
|
||||||
|
"getMinMaxTemp": "从锅炉获取最小/最大温度参数",
|
||||||
|
"ignoreDiagState": "忽略诊断状态",
|
||||||
|
"autoFaultReset": "自动报警复位 <small>(不推荐!)</small>",
|
||||||
|
"autoDiagReset": "自动诊断复位 <small>(不推荐!)</small>",
|
||||||
|
"setDateAndTime": "同步设置锅炉日期与时间",
|
||||||
|
"immergasFix": "针对Immergas锅炉的兼容性修复"
|
||||||
|
},
|
||||||
|
|
||||||
|
"nativeHeating": {
|
||||||
|
"title": "原生锅炉供暖控制",
|
||||||
|
"note": "<u>注意:</u> 仅适用于锅炉需接收目标室温并自主调节载热介质温度的场景,与固件中的PID及Equithermq气候补偿功能不兼容。"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
|
||||||
|
"mqtt": {
|
||||||
|
"homeAssistantDiscovery": "Home Assistant 自动发现",
|
||||||
|
"server": "服务器地址",
|
||||||
|
"port": "端口",
|
||||||
|
"user": "用户名",
|
||||||
|
"password": "密码",
|
||||||
|
"prefix": "Prefix 前缀",
|
||||||
|
"interval": "发布间隔 <small>(秒)</small>"
|
||||||
|
},
|
||||||
|
|
||||||
|
"extPump": {
|
||||||
|
"use": "使用外置循环泵",
|
||||||
|
"gpio": "继电器 GPIO引脚",
|
||||||
|
"postCirculationTime": "后循环时间 <small>(分钟)</small>",
|
||||||
|
"antiStuckInterval": "防卡死间隔时间<small>(天)</small>",
|
||||||
|
"antiStuckTime": "防卡死运行时长<small>(分钟)</small>"
|
||||||
|
},
|
||||||
|
|
||||||
|
"cascadeControl": {
|
||||||
|
"input": {
|
||||||
|
"desc": "仅当另一台锅炉发生故障时启用本锅炉加热。另一台锅炉的控制器需在故障发生时切换GPIO输入状态以触发本功能。",
|
||||||
|
"enable": "启用 input",
|
||||||
|
"gpio": "GPIO",
|
||||||
|
"invertState": "切换 GPIO 状态",
|
||||||
|
"thresholdTime": "状态变化阈值时间<small>(秒)</small>"
|
||||||
|
},
|
||||||
|
"output": {
|
||||||
|
"desc": "可通过<u>继电器</u>控制另一台锅炉的启停。",
|
||||||
|
"enable": "启用 output",
|
||||||
|
"gpio": "GPIO",
|
||||||
|
"invertState": "切换 GPIO 状态",
|
||||||
|
"thresholdTime": "状态变化阈值时间 <small>(秒)</small>",
|
||||||
|
"events": {
|
||||||
|
"desc": "事件",
|
||||||
|
"onFault": "当故障状态激活时",
|
||||||
|
"onLossConnection": "当OpenTherm连接中断时",
|
||||||
|
"onEnabledHeating": "当供暖功能启用时"
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
},
|
||||||
|
|
||||||
|
"upgrade": {
|
||||||
|
"title": "固件升级 - OpenTherm Gateway",
|
||||||
|
"name": "固件升级",
|
||||||
|
|
||||||
|
"section": {
|
||||||
|
"backupAndRestore": "备份与恢复",
|
||||||
|
"backupAndRestore.desc": "本功能支持备份和恢复全部设置",
|
||||||
|
"upgrade": "升级",
|
||||||
|
"upgrade.desc": "本模块支持升级设备的固件与系统文件。<br />可从以下地址下载最新版本 <a href=\"https://github.com/Laxilef/OTGateway/releases\" target=\"_blank\">Releases page</a> 。"
|
||||||
|
},
|
||||||
|
|
||||||
|
"note": {
|
||||||
|
"disclaimer1": "升级系统文件成功后,所有设置将恢复为默认值!升级前请务必备份配置。",
|
||||||
|
"disclaimer2": "升级成功后,设备将在15秒后自动重启。"
|
||||||
|
},
|
||||||
|
|
||||||
|
"settingsFile": "设置文件",
|
||||||
|
"fw": "Firmware",
|
||||||
|
"fs": "Filesystem"
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -117,6 +117,7 @@
|
|||||||
|
|
||||||
"mHeatEnabled": "Heating enabled",
|
"mHeatEnabled": "Heating enabled",
|
||||||
"mHeatBlocking": "Heating blocked",
|
"mHeatBlocking": "Heating blocked",
|
||||||
|
"mHeatOverheat": "Heating overheat",
|
||||||
"sHeatActive": "Heating active",
|
"sHeatActive": "Heating active",
|
||||||
"mHeatSetpointTemp": "Heating setpoint temp",
|
"mHeatSetpointTemp": "Heating setpoint temp",
|
||||||
"mHeatTargetTemp": "Heating target temp",
|
"mHeatTargetTemp": "Heating target temp",
|
||||||
@@ -126,6 +127,7 @@
|
|||||||
"mHeatOutdoorTemp": "Heating, outdoor temp",
|
"mHeatOutdoorTemp": "Heating, outdoor temp",
|
||||||
|
|
||||||
"mDhwEnabled": "DHW enabled",
|
"mDhwEnabled": "DHW enabled",
|
||||||
|
"mDhwOverheat": "DHW overheat",
|
||||||
"sDhwActive": "DHW active",
|
"sDhwActive": "DHW active",
|
||||||
"mDhwTargetTemp": "DHW target temp",
|
"mDhwTargetTemp": "DHW target temp",
|
||||||
"mDhwCurrTemp": "DHW current temp",
|
"mDhwCurrTemp": "DHW current temp",
|
||||||
@@ -201,6 +203,7 @@
|
|||||||
"dhwFlowRate": "DHW, flow rate",
|
"dhwFlowRate": "DHW, flow rate",
|
||||||
"exhaustTemp": "Exhaust temperature",
|
"exhaustTemp": "Exhaust temperature",
|
||||||
"modLevel": "Modulation level (in percents)",
|
"modLevel": "Modulation level (in percents)",
|
||||||
|
"number": "Number (raw)",
|
||||||
"powerFactor": "Power (in percent)",
|
"powerFactor": "Power (in percent)",
|
||||||
"power": "Power (in kWt)",
|
"power": "Power (in kWt)",
|
||||||
"fanSpeed": "Fan speed",
|
"fanSpeed": "Fan speed",
|
||||||
@@ -231,6 +234,14 @@
|
|||||||
"otSolarCollectorTemp": "OpenTherm, solar collector temp",
|
"otSolarCollectorTemp": "OpenTherm, solar collector temp",
|
||||||
"otFanSpeedSetpoint": "OpenTherm, setpoint fan speed",
|
"otFanSpeedSetpoint": "OpenTherm, setpoint fan speed",
|
||||||
"otFanSpeedCurrent": "OpenTherm, current fan speed",
|
"otFanSpeedCurrent": "OpenTherm, current fan speed",
|
||||||
|
"otBurnerStarts": "OpenTherm, number of burner starts",
|
||||||
|
"otDhwBurnerStarts": "OpenTherm, number of burner starts (DHW)",
|
||||||
|
"otHeatingPumpStarts": "OpenTherm, number of pump starts (heating)",
|
||||||
|
"otDhwPumpStarts": "OpenTherm, number of pump starts (DHW)",
|
||||||
|
"otBurnerHours": "OpenTherm, number of burner operating hours",
|
||||||
|
"otDhwBurnerHours": "OpenTherm, number of burner operating hours (DHW)",
|
||||||
|
"otHeatingPumpHours": "OpenTherm, number of pump operating hours (heating)",
|
||||||
|
"otDhwPumpHours": "OpenTherm, number of pump operating hours (DHW)",
|
||||||
|
|
||||||
"ntcTemp": "NTC sensor",
|
"ntcTemp": "NTC sensor",
|
||||||
"dallasTemp": "DALLAS sensor",
|
"dallasTemp": "DALLAS sensor",
|
||||||
@@ -292,6 +303,25 @@
|
|||||||
"min": "Minimum temperature",
|
"min": "Minimum temperature",
|
||||||
"max": "Maximum temperature"
|
"max": "Maximum temperature"
|
||||||
},
|
},
|
||||||
|
"maxModulation": "Max modulation level",
|
||||||
|
"ohProtection": {
|
||||||
|
"title": "Overheating protection",
|
||||||
|
"desc": "<b>Note:</b> This feature can be useful if the built-in boiler overheating protection does not work or does not work correctly and the heat carrier boils. To disable, set 0 as <b>high</b> and <b>low</b> temperature.",
|
||||||
|
"highTemp": {
|
||||||
|
"title": "High temperature threshold",
|
||||||
|
"note": "Threshold at which the burner will be forcibly switched off"
|
||||||
|
},
|
||||||
|
"lowTemp": {
|
||||||
|
"title": "Low temperature threshold",
|
||||||
|
"note": "Threshold at which the burner can be turned on again"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"freezeProtection": {
|
||||||
|
"title": "Freeze protection",
|
||||||
|
"desc": "Heating will be forced to turn on if the heat carrier or indoor temperature drops below <b>Low temperature</b> during <b>Waiting time</b>.",
|
||||||
|
"lowTemp": "Low temperature threshold",
|
||||||
|
"thresholdTime": "Waiting time <small>(sec)</small>"
|
||||||
|
},
|
||||||
|
|
||||||
"portal": {
|
"portal": {
|
||||||
"login": "Login",
|
"login": "Login",
|
||||||
@@ -375,7 +405,6 @@
|
|||||||
"ledGpio": "RX LED GPIO",
|
"ledGpio": "RX LED GPIO",
|
||||||
"memberId": "Master member ID",
|
"memberId": "Master member ID",
|
||||||
"flags": "Master flags",
|
"flags": "Master flags",
|
||||||
"maxMod": "Max modulation level",
|
|
||||||
"minPower": {
|
"minPower": {
|
||||||
"title": "Min boiler power <small>(kW)</small>",
|
"title": "Min boiler power <small>(kW)</small>",
|
||||||
"note": "This value is at 0-1% boiler modulation level. Typically found in the boiler specification as \"minimum useful heat output\"."
|
"note": "This value is at 0-1% boiler modulation level. Typically found in the boiler specification as \"minimum useful heat output\"."
|
||||||
@@ -386,7 +415,8 @@
|
|||||||
},
|
},
|
||||||
|
|
||||||
"options": {
|
"options": {
|
||||||
"desc": "Options",
|
"title": "Options (additional settings)",
|
||||||
|
"desc": "Options can change the logic of the boiler. Not all options are documented in the protocol, so the same option can have different effects on different boilers.<br /><b>Note:</b> There is no need to change anything if everything works well.",
|
||||||
"dhwSupport": "DHW support",
|
"dhwSupport": "DHW support",
|
||||||
"coolingSupport": "Cooling support",
|
"coolingSupport": "Cooling support",
|
||||||
"summerWinterMode": "Summer/winter mode",
|
"summerWinterMode": "Summer/winter mode",
|
||||||
@@ -395,9 +425,13 @@
|
|||||||
"heatingToCh2": "Duplicate heating to CH2",
|
"heatingToCh2": "Duplicate heating to CH2",
|
||||||
"dhwToCh2": "Duplicate DHW to CH2",
|
"dhwToCh2": "Duplicate DHW to CH2",
|
||||||
"dhwBlocking": "DHW blocking",
|
"dhwBlocking": "DHW blocking",
|
||||||
"modulationSyncWithHeating": "Sync modulation with heating",
|
"dhwStateAsDhwBlocking": "DHW state as DHW blocking",
|
||||||
"maxTempSyncWithTargetTemp": "Sync max heating temp with target temp",
|
"maxTempSyncWithTargetTemp": "Sync max heating temp with target temp",
|
||||||
"getMinMaxTemp": "Get min/max temp from boiler",
|
"getMinMaxTemp": "Get min/max temp from boiler",
|
||||||
|
"ignoreDiagState": "Ignore diag state",
|
||||||
|
"autoFaultReset": "Auto fault reset <small>(not recommended!)</small>",
|
||||||
|
"autoDiagReset": "Auto diag reset <small>(not recommended!)</small>",
|
||||||
|
"setDateAndTime": "Set date & time on boiler",
|
||||||
"immergasFix": "Fix for Immergas boilers"
|
"immergasFix": "Fix for Immergas boilers"
|
||||||
},
|
},
|
||||||
|
|
||||||
|
|||||||
@@ -117,6 +117,7 @@
|
|||||||
|
|
||||||
"mHeatEnabled": "Riscaldamento attivato",
|
"mHeatEnabled": "Riscaldamento attivato",
|
||||||
"mHeatBlocking": "Riscaldamento bloccato",
|
"mHeatBlocking": "Riscaldamento bloccato",
|
||||||
|
"mHeatOverheat": "Riscaldamento surriscaldamento",
|
||||||
"sHeatActive": "Riscaldamento attivo",
|
"sHeatActive": "Riscaldamento attivo",
|
||||||
"mHeatSetpointTemp": "Temp riscaldamento impostato",
|
"mHeatSetpointTemp": "Temp riscaldamento impostato",
|
||||||
"mHeatTargetTemp": "Target Temp caldaia",
|
"mHeatTargetTemp": "Target Temp caldaia",
|
||||||
@@ -126,6 +127,7 @@
|
|||||||
"mHeatOutdoorTemp": "Riscaldamento, temp esterna",
|
"mHeatOutdoorTemp": "Riscaldamento, temp esterna",
|
||||||
|
|
||||||
"mDhwEnabled": "ACS attivata",
|
"mDhwEnabled": "ACS attivata",
|
||||||
|
"mDhwOverheat": "ACS surriscaldamento",
|
||||||
"sDhwActive": "ACS attiva",
|
"sDhwActive": "ACS attiva",
|
||||||
"mDhwTargetTemp": "ACS temp impostata",
|
"mDhwTargetTemp": "ACS temp impostata",
|
||||||
"mDhwCurrTemp": "ACS temp attuale",
|
"mDhwCurrTemp": "ACS temp attuale",
|
||||||
@@ -201,6 +203,7 @@
|
|||||||
"dhwFlowRate": "ACS, prelievo",
|
"dhwFlowRate": "ACS, prelievo",
|
||||||
"exhaustTemp": "Temperatura fumi",
|
"exhaustTemp": "Temperatura fumi",
|
||||||
"modLevel": "Livello Modulazione (%)",
|
"modLevel": "Livello Modulazione (%)",
|
||||||
|
"number": "Numero (raw)",
|
||||||
"powerFactor": "Potenza (%)",
|
"powerFactor": "Potenza (%)",
|
||||||
"power": "Potenza (in kW)",
|
"power": "Potenza (in kW)",
|
||||||
"fanSpeed": "Velocità ventilatore",
|
"fanSpeed": "Velocità ventilatore",
|
||||||
@@ -231,6 +234,14 @@
|
|||||||
"otSolarCollectorTemp": "OpenTherm, temp collettore solare",
|
"otSolarCollectorTemp": "OpenTherm, temp collettore solare",
|
||||||
"otFanSpeedSetpoint": "OpenTherm, velocità ventola impostata",
|
"otFanSpeedSetpoint": "OpenTherm, velocità ventola impostata",
|
||||||
"otFanSpeedCurrent": "OpenTherm, velocità ventola attuale",
|
"otFanSpeedCurrent": "OpenTherm, velocità ventola attuale",
|
||||||
|
"otBurnerStarts": "OpenTherm, numero di avviamenti del bruciatore",
|
||||||
|
"otDhwBurnerStarts": "OpenTherm, numero di avviamenti del bruciatore (ACS)",
|
||||||
|
"otHeatingPumpStarts": "OpenTherm, numero di avviamenti della pompa (riscaldamento)",
|
||||||
|
"otDhwPumpStarts": "OpenTherm, numero di avviamenti della pompa (ACS)",
|
||||||
|
"otBurnerHours": "OpenTherm, numero di ore di funzionamento del bruciatore",
|
||||||
|
"otDhwBurnerHours": "OpenTherm, numero di ore di funzionamento del bruciatore (ACS)",
|
||||||
|
"otHeatingPumpHours": "OpenTherm, numero di ore di funzionamento della pompa (riscaldamento)",
|
||||||
|
"otDhwPumpHours": "OpenTherm, numero di ore di funzionamento della pompa (ACS)",
|
||||||
|
|
||||||
"ntcTemp": "Sensore NTC",
|
"ntcTemp": "Sensore NTC",
|
||||||
"dallasTemp": "Sensore DALLAS",
|
"dallasTemp": "Sensore DALLAS",
|
||||||
@@ -292,6 +303,25 @@
|
|||||||
"min": "Temperatura minima",
|
"min": "Temperatura minima",
|
||||||
"max": "Temperatura massima"
|
"max": "Temperatura massima"
|
||||||
},
|
},
|
||||||
|
"maxModulation": "Max livello modulazione",
|
||||||
|
"ohProtection": {
|
||||||
|
"title": "Protezione contro il surriscaldamento",
|
||||||
|
"desc": "<b>Nota:</b> questa funzione può essere utile se la protezione contro il surriscaldamento integrata nella caldaia non funziona o non funziona correttamente e il fluido termovettore bolle. Per disattivarla, impostare 0 come temperatura <b>alta</b> e <b>bassa</b>.",
|
||||||
|
"highTemp": {
|
||||||
|
"title": "Soglia di temperatura alta",
|
||||||
|
"note": "Soglia alla quale il bruciatore verrà spento forzatamente"
|
||||||
|
},
|
||||||
|
"lowTemp": {
|
||||||
|
"title": "Soglia di temperatura bassa",
|
||||||
|
"note": "Soglia alla quale il bruciatore può essere riacceso"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"freezeProtection": {
|
||||||
|
"title": "Protezione antigelo",
|
||||||
|
"desc": "Il riscaldamento verrà attivato forzatamente se la temperatura del vettore di calore o interna scende al di sotto della <b>temperatura minima</b> durante il <b>tempo di attesa</b>.",
|
||||||
|
"lowTemp": "Soglia di temperatura minima",
|
||||||
|
"thresholdTime": "Tempo di attesa <small>(sec)</small>"
|
||||||
|
},
|
||||||
|
|
||||||
"portal": {
|
"portal": {
|
||||||
"login": "Login",
|
"login": "Login",
|
||||||
@@ -375,7 +405,6 @@
|
|||||||
"ledGpio": "RX LED GPIO",
|
"ledGpio": "RX LED GPIO",
|
||||||
"memberId": "Master member ID",
|
"memberId": "Master member ID",
|
||||||
"flags": "Master flags",
|
"flags": "Master flags",
|
||||||
"maxMod": "Max livello modulazione",
|
|
||||||
"minPower": {
|
"minPower": {
|
||||||
"title": "Potenza minima caldaia <small>(kW)</small>",
|
"title": "Potenza minima caldaia <small>(kW)</small>",
|
||||||
"note": "Questo valore corrisponde allo livello 0-1% di modulazione della caldaia. Di solito si trova nelle specifiche delle caldaia come \"potenza minima disponibile\"."
|
"note": "Questo valore corrisponde allo livello 0-1% di modulazione della caldaia. Di solito si trova nelle specifiche delle caldaia come \"potenza minima disponibile\"."
|
||||||
@@ -386,7 +415,8 @@
|
|||||||
},
|
},
|
||||||
|
|
||||||
"options": {
|
"options": {
|
||||||
"desc": "Opzioni",
|
"title": "Opzioni (impostazioni aggiuntive)",
|
||||||
|
"desc": "Le opzioni possono modificare la logica della caldaia. Non tutte le opzioni sono documentate nel protocollo, quindi la stessa opzione può avere effetti diversi su caldaie diverse.<br /><b>Nota:</b> Non è necessario modificare nulla se tutto funziona correttamente.",
|
||||||
"dhwSupport": "Supporto ACS",
|
"dhwSupport": "Supporto ACS",
|
||||||
"coolingSupport": "Supporto rafferscamento",
|
"coolingSupport": "Supporto rafferscamento",
|
||||||
"summerWinterMode": "Modalità Estate/inverno",
|
"summerWinterMode": "Modalità Estate/inverno",
|
||||||
@@ -395,9 +425,13 @@
|
|||||||
"heatingToCh2": "Riproduci riscaldamento su CH2",
|
"heatingToCh2": "Riproduci riscaldamento su CH2",
|
||||||
"dhwToCh2": "Riproduci ACS su CH2",
|
"dhwToCh2": "Riproduci ACS su CH2",
|
||||||
"dhwBlocking": "Bloccare ACS",
|
"dhwBlocking": "Bloccare ACS",
|
||||||
"modulationSyncWithHeating": "Sincronizzare modulazione con caldaia",
|
"dhwStateAsDhwBlocking": "Stato ACS come bloccare ACS",
|
||||||
"maxTempSyncWithTargetTemp": "Sincronizza la temperatura massima di riscaldamento con la temperatura target",
|
"maxTempSyncWithTargetTemp": "Sincronizza la temperatura massima di riscaldamento con la temperatura target",
|
||||||
"getMinMaxTemp": "Prendi temp min/max dalla caldaia",
|
"getMinMaxTemp": "Prendi temp min/max dalla caldaia",
|
||||||
|
"ignoreDiagState": "Ignora lo stato diagnostico",
|
||||||
|
"autoFaultReset": "Ripristino automatico degli errori <small>(sconsigliato!)</small>",
|
||||||
|
"autoDiagReset": "Ripristino diagnostico automatica <small>(sconsigliato!)</small>",
|
||||||
|
"setDateAndTime": "Imposta data e ora sulla caldaia",
|
||||||
"immergasFix": "Fix per caldiaie Immergas"
|
"immergasFix": "Fix per caldiaie Immergas"
|
||||||
},
|
},
|
||||||
|
|
||||||
|
|||||||
@@ -117,6 +117,7 @@
|
|||||||
|
|
||||||
"mHeatEnabled": "Отопление",
|
"mHeatEnabled": "Отопление",
|
||||||
"mHeatBlocking": "Блокировка отопления",
|
"mHeatBlocking": "Блокировка отопления",
|
||||||
|
"mHeatOverheat": "Отопление, перегрев",
|
||||||
"sHeatActive": "Активность отопления",
|
"sHeatActive": "Активность отопления",
|
||||||
"mHeatSetpointTemp": "Отопление, уставка",
|
"mHeatSetpointTemp": "Отопление, уставка",
|
||||||
"mHeatTargetTemp": "Отопление, целевая температура",
|
"mHeatTargetTemp": "Отопление, целевая температура",
|
||||||
@@ -126,6 +127,7 @@
|
|||||||
"mHeatOutdoorTemp": "Отопление, наружная темп.",
|
"mHeatOutdoorTemp": "Отопление, наружная темп.",
|
||||||
|
|
||||||
"mDhwEnabled": "ГВС",
|
"mDhwEnabled": "ГВС",
|
||||||
|
"mDhwOverheat": "ГВС, перегрев",
|
||||||
"sDhwActive": "Активность ГВС",
|
"sDhwActive": "Активность ГВС",
|
||||||
"mDhwTargetTemp": "ГВС, целевая температура",
|
"mDhwTargetTemp": "ГВС, целевая температура",
|
||||||
"mDhwCurrTemp": "ГВС, текущая температура",
|
"mDhwCurrTemp": "ГВС, текущая температура",
|
||||||
@@ -201,6 +203,7 @@
|
|||||||
"dhwFlowRate": "ГВС, расход/скорость потока",
|
"dhwFlowRate": "ГВС, расход/скорость потока",
|
||||||
"exhaustTemp": "Температура выхлопных газов",
|
"exhaustTemp": "Температура выхлопных газов",
|
||||||
"modLevel": "Уровень модуляции (в процентах)",
|
"modLevel": "Уровень модуляции (в процентах)",
|
||||||
|
"number": "Число (raw)",
|
||||||
"powerFactor": "Мощность (в процентах)",
|
"powerFactor": "Мощность (в процентах)",
|
||||||
"power": "Мощность (в кВт)",
|
"power": "Мощность (в кВт)",
|
||||||
"fanSpeed": "Скорость вентилятора",
|
"fanSpeed": "Скорость вентилятора",
|
||||||
@@ -231,6 +234,14 @@
|
|||||||
"otSolarCollectorTemp": "OpenTherm, темп. солн. коллектора",
|
"otSolarCollectorTemp": "OpenTherm, темп. солн. коллектора",
|
||||||
"otFanSpeedSetpoint": "OpenTherm, установленная мощн. вентилятора",
|
"otFanSpeedSetpoint": "OpenTherm, установленная мощн. вентилятора",
|
||||||
"otFanSpeedCurrent": "OpenTherm, текущая мощн. вентилятора",
|
"otFanSpeedCurrent": "OpenTherm, текущая мощн. вентилятора",
|
||||||
|
"otBurnerStarts": "OpenTherm, кол-во запусков горелки",
|
||||||
|
"otDhwBurnerStarts": "OpenTherm, кол-во запусков горелки (ГВС)",
|
||||||
|
"otHeatingPumpStarts": "OpenTherm, кол-во запусков насоса (отопление)",
|
||||||
|
"otDhwPumpStarts": "OpenTherm, кол-во запусков насоса (ГВС)",
|
||||||
|
"otBurnerHours": "OpenTherm, кол-во часов работы горелки",
|
||||||
|
"otDhwBurnerHours": "OpenTherm, кол-во часов работы горелки (ГВС)",
|
||||||
|
"otHeatingPumpHours": "OpenTherm, кол-во часов работы насоса (отопление)",
|
||||||
|
"otDhwPumpHours": "OpenTherm, кол-во часов работы насоса (ГВС)",
|
||||||
|
|
||||||
"ntcTemp": "NTC датчик",
|
"ntcTemp": "NTC датчик",
|
||||||
"dallasTemp": "DALLAS датчик",
|
"dallasTemp": "DALLAS датчик",
|
||||||
@@ -292,6 +303,25 @@
|
|||||||
"min": "Мин. температура",
|
"min": "Мин. температура",
|
||||||
"max": "Макс. температура"
|
"max": "Макс. температура"
|
||||||
},
|
},
|
||||||
|
"maxModulation": "Макс. уровень модуляции",
|
||||||
|
"ohProtection": {
|
||||||
|
"title": "Защита от перегрева",
|
||||||
|
"desc": "<b>Примечание:</b> Эта функция может быть полезна, если встроенная защита от перегрева котла не срабатывает или срабатывает некорректно и теплоноситель закипает. Для отключения установите 0 в качестве <b>верхнего</b> и <b>нижнего</b> порога температуры.",
|
||||||
|
"highTemp": {
|
||||||
|
"title": "Верхний порог температуры",
|
||||||
|
"note": "Порог, при котором горелка будет принудительно отключена"
|
||||||
|
},
|
||||||
|
"lowTemp": {
|
||||||
|
"title": "Нижний порог температуры",
|
||||||
|
"note": "Порог, при котором горелка может быть включена снова"
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"freezeProtection": {
|
||||||
|
"title": "Защита от замерзания",
|
||||||
|
"desc": "Отопление будет принудительно включено, если темп. теплоносителя или внутренняя темп. опустится ниже <b>нижнего порога</b> в течение <b>времени ожидания</b>.",
|
||||||
|
"lowTemp": "Нижний порог температуры",
|
||||||
|
"thresholdTime": "Время ожидания <small>(сек)</small>"
|
||||||
|
},
|
||||||
|
|
||||||
"portal": {
|
"portal": {
|
||||||
"login": "Логин",
|
"login": "Логин",
|
||||||
@@ -375,7 +405,6 @@
|
|||||||
"ledGpio": "RX LED GPIO",
|
"ledGpio": "RX LED GPIO",
|
||||||
"memberId": "Master member ID",
|
"memberId": "Master member ID",
|
||||||
"flags": "Master flags",
|
"flags": "Master flags",
|
||||||
"maxMod": "Макс. уровень модуляции",
|
|
||||||
"minPower": {
|
"minPower": {
|
||||||
"title": "Мин. мощность котла <small>(кВт)</small>",
|
"title": "Мин. мощность котла <small>(кВт)</small>",
|
||||||
"note": "Это значение соответствует уровню модуляции котла 0–1%. Обычно можно найти в спецификации котла как \"минимальная полезная тепловая мощность\"."
|
"note": "Это значение соответствует уровню модуляции котла 0–1%. Обычно можно найти в спецификации котла как \"минимальная полезная тепловая мощность\"."
|
||||||
@@ -386,7 +415,8 @@
|
|||||||
},
|
},
|
||||||
|
|
||||||
"options": {
|
"options": {
|
||||||
"desc": "Опции",
|
"title": "Опции (дополнительные настройки)",
|
||||||
|
"desc": "Опции могут менять логику работы котла. Не все опции задокументированы в протоколе, поэтому одна и та же опция может иметь разный эффект на разных котлах.<br /><b>Примечание:</b> Нет необходимости что-то менять, если всё работает хорошо.",
|
||||||
"dhwSupport": "Поддержка ГВС",
|
"dhwSupport": "Поддержка ГВС",
|
||||||
"coolingSupport": "Поддержка охлаждения",
|
"coolingSupport": "Поддержка охлаждения",
|
||||||
"summerWinterMode": "Летний/зимний режим",
|
"summerWinterMode": "Летний/зимний режим",
|
||||||
@@ -395,9 +425,13 @@
|
|||||||
"heatingToCh2": "Дублировать параметры отопления в канал 2",
|
"heatingToCh2": "Дублировать параметры отопления в канал 2",
|
||||||
"dhwToCh2": "Дублировать параметры ГВС в канал 2",
|
"dhwToCh2": "Дублировать параметры ГВС в канал 2",
|
||||||
"dhwBlocking": "DHW blocking",
|
"dhwBlocking": "DHW blocking",
|
||||||
"modulationSyncWithHeating": "Синхронизировать модуляцию с отоплением",
|
"dhwStateAsDhwBlocking": "DHW blocking в качестве состояния ГВС",
|
||||||
"maxTempSyncWithTargetTemp": "Синхронизировать макс. темп. отопления с целевой темп.",
|
"maxTempSyncWithTargetTemp": "Синхронизировать макс. темп. отопления с целевой темп.",
|
||||||
"getMinMaxTemp": "Получать мин. и макс. температуру от котла",
|
"getMinMaxTemp": "Получать мин. и макс. температуру от котла",
|
||||||
|
"ignoreDiagState": "Игнорировать состояние диагностики",
|
||||||
|
"autoFaultReset": "Автоматический сброс ошибок <small>(не рекомендуется!)</small>",
|
||||||
|
"autoDiagReset": "Автоматический сброс диагностики <small>(не рекомендуется!)</small>",
|
||||||
|
"setDateAndTime": "Устанавливать время и дату на котле",
|
||||||
"immergasFix": "Фикс для котлов Immergas"
|
"immergasFix": "Фикс для котлов Immergas"
|
||||||
},
|
},
|
||||||
|
|
||||||
|
|||||||
@@ -21,6 +21,7 @@
|
|||||||
<li>
|
<li>
|
||||||
<select id="lang" aria-label="Lang">
|
<select id="lang" aria-label="Lang">
|
||||||
<option value="en" selected>EN</option>
|
<option value="en" selected>EN</option>
|
||||||
|
<option value="cn">CN</option>
|
||||||
<option value="it">IT</option>
|
<option value="it">IT</option>
|
||||||
<option value="ru">RU</option>
|
<option value="ru">RU</option>
|
||||||
</select>
|
</select>
|
||||||
@@ -184,6 +185,10 @@
|
|||||||
<th scope="row" data-i18n>dashboard.states.mHeatBlocking</th>
|
<th scope="row" data-i18n>dashboard.states.mHeatBlocking</th>
|
||||||
<td><i class="mHeatBlocking"></i></td>
|
<td><i class="mHeatBlocking"></i></td>
|
||||||
</tr>
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<th scope="row" data-i18n>dashboard.states.mHeatOverheat</th>
|
||||||
|
<td><i class="mHeatOverheat"></i></td>
|
||||||
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
<th scope="row" data-i18n>dashboard.states.sHeatActive</th>
|
<th scope="row" data-i18n>dashboard.states.sHeatActive</th>
|
||||||
<td><i class="sHeatActive"></i></td>
|
<td><i class="sHeatActive"></i></td>
|
||||||
@@ -218,6 +223,10 @@
|
|||||||
<th scope="row" data-i18n>dashboard.states.mDhwEnabled</th>
|
<th scope="row" data-i18n>dashboard.states.mDhwEnabled</th>
|
||||||
<td><i class="mDhwEnabled"></i></td>
|
<td><i class="mDhwEnabled"></i></td>
|
||||||
</tr>
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<th scope="row" data-i18n>dashboard.states.mDhwOverheat</th>
|
||||||
|
<td><i class="mDhwOverheat"></i></td>
|
||||||
|
</tr>
|
||||||
<tr>
|
<tr>
|
||||||
<th scope="row" data-i18n>dashboard.states.sDhwActive</th>
|
<th scope="row" data-i18n>dashboard.states.sDhwActive</th>
|
||||||
<td><i class="sDhwActive"></i></td>
|
<td><i class="sDhwActive"></i></td>
|
||||||
@@ -261,16 +270,16 @@
|
|||||||
|
|
||||||
<details>
|
<details>
|
||||||
<summary><b data-i18n>dashboard.section.diag</b></summary>
|
<summary><b data-i18n>dashboard.section.diag</b></summary>
|
||||||
<pre><b>Vendor:</b> <span class="sVendor"></span>
|
<pre><b>Vendor:</b> <span class="sVendor"></span>
|
||||||
<b>Member ID:</b> <span class="sMemberId"></span>
|
<b>Member ID:</b> <span class="sMemberId"></span>
|
||||||
<b>Flags:</b> <span class="sFlags"></span>
|
<b>Flags:</b> <span class="sFlags"></span>
|
||||||
<b>Type:</b> <span class="sType"></span>
|
<b>Type:</b> <span class="sType"></span>
|
||||||
<b>AppVersion:</b> <span class="sAppVersion"></span>
|
<b>AppVersion:</b> <span class="sAppVersion"></span>
|
||||||
<b>OT version:</b> <span class="sProtocolVersion"></span>
|
<b>OT version:</b> <span class="sProtocolVersion"></span>
|
||||||
<b>Modulation limits:</b> <span class="sModMin"></span>...<span class="sAbsModMax"></span> %, curr. max: <span class="sModMax"></span> %
|
<b>Modulation:</b> min: <span class="sModMin"></span> %, curr. max: <span class="sModMax"></span> %
|
||||||
<b>Power limits:</b> <span class="sPowerMin"></span>...<span class="sPowerMax"></span> kW
|
<b>Power limits:</b> <span class="sPowerMin"></span>...<span class="sPowerMax"></span> kW
|
||||||
<b>Heating limits:</b> <span class="sHeatMinTemp"></span>...<span class="sHeatMaxTemp"></span> <span class="tempUnit"></span>
|
<b>Heating limits:</b> <span class="sHeatMinTemp"></span>...<span class="sHeatMaxTemp"></span> <span class="tempUnit"></span>
|
||||||
<b>DHW limits:</b> <span class="sDhwMinTemp"></span>...<span class="sDhwMaxTemp"></span> <span class="tempUnit"></span></pre>
|
<b>DHW limits:</b> <span class="sDhwMinTemp"></span>...<span class="sDhwMaxTemp"></span> <span class="tempUnit"></span></pre>
|
||||||
</details>
|
</details>
|
||||||
</div>
|
</div>
|
||||||
</article>
|
</article>
|
||||||
@@ -508,7 +517,6 @@
|
|||||||
setValue('.tempUnit', temperatureUnit(unitSystem));
|
setValue('.tempUnit', temperatureUnit(unitSystem));
|
||||||
setValue('.pressureUnit', pressureUnit(unitSystem));
|
setValue('.pressureUnit', pressureUnit(unitSystem));
|
||||||
setValue('.volumeUnit', volumeUnit(unitSystem));
|
setValue('.volumeUnit', volumeUnit(unitSystem));
|
||||||
setValue('.sAbsModMax', result.opentherm.maxModulation);
|
|
||||||
|
|
||||||
} catch (error) {
|
} catch (error) {
|
||||||
console.log(error);
|
console.log(error);
|
||||||
@@ -612,6 +620,11 @@
|
|||||||
result.master.heating.blocking ? "red" : "green"
|
result.master.heating.blocking ? "red" : "green"
|
||||||
);
|
);
|
||||||
setState('.mHeatIndoorTempControl', result.master.heating.indoorTempControl);
|
setState('.mHeatIndoorTempControl', result.master.heating.indoorTempControl);
|
||||||
|
setStatus(
|
||||||
|
'.mHeatOverheat',
|
||||||
|
result.master.heating.overheat ? "success" : "error",
|
||||||
|
result.master.heating.overheat ? "red" : "green"
|
||||||
|
);
|
||||||
setValue('.mHeatSetpointTemp', result.master.heating.setpointTemp);
|
setValue('.mHeatSetpointTemp', result.master.heating.setpointTemp);
|
||||||
setValue('.mHeatTargetTemp', result.master.heating.targetTemp);
|
setValue('.mHeatTargetTemp', result.master.heating.targetTemp);
|
||||||
setValue('.mHeatCurrTemp', result.master.heating.currentTemp);
|
setValue('.mHeatCurrTemp', result.master.heating.currentTemp);
|
||||||
@@ -622,6 +635,11 @@
|
|||||||
setValue('.mHeatMaxTemp', result.master.heating.maxTemp);
|
setValue('.mHeatMaxTemp', result.master.heating.maxTemp);
|
||||||
|
|
||||||
setState('.mDhwEnabled', result.master.dhw.enabled);
|
setState('.mDhwEnabled', result.master.dhw.enabled);
|
||||||
|
setStatus(
|
||||||
|
'.mDhwOverheat',
|
||||||
|
result.master.dhw.overheat ? "success" : "error",
|
||||||
|
result.master.dhw.overheat ? "red" : "green"
|
||||||
|
);
|
||||||
setValue('.mDhwTargetTemp', result.master.dhw.targetTemp);
|
setValue('.mDhwTargetTemp', result.master.dhw.targetTemp);
|
||||||
setValue('.mDhwCurrTemp', result.master.dhw.currentTemp);
|
setValue('.mDhwCurrTemp', result.master.dhw.currentTemp);
|
||||||
setValue('.mDhwRetTemp', result.master.dhw.returnTemp);
|
setValue('.mDhwRetTemp', result.master.dhw.returnTemp);
|
||||||
|
|||||||
@@ -21,6 +21,7 @@
|
|||||||
<li>
|
<li>
|
||||||
<select id="lang" aria-label="Lang">
|
<select id="lang" aria-label="Lang">
|
||||||
<option value="en" selected>EN</option>
|
<option value="en" selected>EN</option>
|
||||||
|
<option value="cn">CN</option>
|
||||||
<option value="it">IT</option>
|
<option value="it">IT</option>
|
||||||
<option value="ru">RU</option>
|
<option value="ru">RU</option>
|
||||||
</select>
|
</select>
|
||||||
|
|||||||
@@ -21,6 +21,7 @@
|
|||||||
<li>
|
<li>
|
||||||
<select id="lang" aria-label="Lang">
|
<select id="lang" aria-label="Lang">
|
||||||
<option value="en" selected>EN</option>
|
<option value="en" selected>EN</option>
|
||||||
|
<option value="cn">CN</option>
|
||||||
<option value="it">IT</option>
|
<option value="it">IT</option>
|
||||||
<option value="ru">RU</option>
|
<option value="ru">RU</option>
|
||||||
</select>
|
</select>
|
||||||
|
|||||||
@@ -21,6 +21,7 @@
|
|||||||
<li>
|
<li>
|
||||||
<select id="lang" aria-label="Lang">
|
<select id="lang" aria-label="Lang">
|
||||||
<option value="en" selected>EN</option>
|
<option value="en" selected>EN</option>
|
||||||
|
<option value="cn">CN</option>
|
||||||
<option value="it">IT</option>
|
<option value="it">IT</option>
|
||||||
<option value="ru">RU</option>
|
<option value="ru">RU</option>
|
||||||
</select>
|
</select>
|
||||||
@@ -69,6 +70,7 @@
|
|||||||
<option value="6" data-i18n>sensors.purposes.dhwFlowRate</option>
|
<option value="6" data-i18n>sensors.purposes.dhwFlowRate</option>
|
||||||
<option value="7" data-i18n>sensors.purposes.exhaustTemp</option>
|
<option value="7" data-i18n>sensors.purposes.exhaustTemp</option>
|
||||||
<option value="8" data-i18n>sensors.purposes.modLevel</option>
|
<option value="8" data-i18n>sensors.purposes.modLevel</option>
|
||||||
|
<option value="247" data-i18n>sensors.purposes.number</option>
|
||||||
<option value="248" data-i18n>sensors.purposes.powerFactor</option>
|
<option value="248" data-i18n>sensors.purposes.powerFactor</option>
|
||||||
<option value="249" data-i18n>sensors.purposes.power</option>
|
<option value="249" data-i18n>sensors.purposes.power</option>
|
||||||
<option value="250" data-i18n>sensors.purposes.fanSpeed</option>
|
<option value="250" data-i18n>sensors.purposes.fanSpeed</option>
|
||||||
@@ -102,6 +104,14 @@
|
|||||||
<option value="16" data-i18n>sensors.types.otSolarCollectorTemp</option>
|
<option value="16" data-i18n>sensors.types.otSolarCollectorTemp</option>
|
||||||
<option value="17" data-i18n>sensors.types.otFanSpeedSetpoint</option>
|
<option value="17" data-i18n>sensors.types.otFanSpeedSetpoint</option>
|
||||||
<option value="18" data-i18n>sensors.types.otFanSpeedCurrent</option>
|
<option value="18" data-i18n>sensors.types.otFanSpeedCurrent</option>
|
||||||
|
<option value="19" data-i18n>sensors.types.otBurnerStarts</option>
|
||||||
|
<option value="20" data-i18n>sensors.types.otDhwBurnerStarts</option>
|
||||||
|
<option value="21" data-i18n>sensors.types.otHeatingPumpStarts</option>
|
||||||
|
<option value="22" data-i18n>sensors.types.otDhwPumpStarts</option>
|
||||||
|
<option value="23" data-i18n>sensors.types.otBurnerHours</option>
|
||||||
|
<option value="24" data-i18n>sensors.types.otDhwBurnerHours</option>
|
||||||
|
<option value="25" data-i18n>sensors.types.otHeatingPumpHours</option>
|
||||||
|
<option value="26" data-i18n>sensors.types.otDhwPumpHours</option>
|
||||||
|
|
||||||
<option value="50" data-i18n>sensors.types.ntcTemp</option>
|
<option value="50" data-i18n>sensors.types.ntcTemp</option>
|
||||||
<option value="51" data-i18n>sensors.types.dallasTemp</option>
|
<option value="51" data-i18n>sensors.types.dallasTemp</option>
|
||||||
|
|||||||
@@ -21,6 +21,7 @@
|
|||||||
<li>
|
<li>
|
||||||
<select id="lang" aria-label="Lang">
|
<select id="lang" aria-label="Lang">
|
||||||
<option value="en" selected>EN</option>
|
<option value="en" selected>EN</option>
|
||||||
|
<option value="cn">CN</option>
|
||||||
<option value="it">IT</option>
|
<option value="it">IT</option>
|
||||||
<option value="ru">RU</option>
|
<option value="ru">RU</option>
|
||||||
</select>
|
</select>
|
||||||
@@ -202,6 +203,55 @@
|
|||||||
</label>
|
</label>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
|
<label>
|
||||||
|
<span data-i18n>settings.maxModulation</span>
|
||||||
|
<input type="number" inputmode="numeric" name="heating[maxModulation]" min="1" max="100" step="1" required>
|
||||||
|
</label>
|
||||||
|
|
||||||
|
<hr />
|
||||||
|
|
||||||
|
<details>
|
||||||
|
<summary><b data-i18n>settings.ohProtection.title</b></summary>
|
||||||
|
|
||||||
|
<div class="grid">
|
||||||
|
<label>
|
||||||
|
<span data-i18n>settings.ohProtection.highTemp.title</span>
|
||||||
|
<input type="number" inputmode="numeric" name="heating[overheatProtection][highTemp]" min="0" max="0" step="1" required>
|
||||||
|
<small data-i18n>settings.ohProtection.highTemp.note</small>
|
||||||
|
</label>
|
||||||
|
|
||||||
|
<label>
|
||||||
|
<span data-i18n>settings.ohProtection.lowTemp.title</span>
|
||||||
|
<input type="number" inputmode="numeric" name="heating[overheatProtection][lowTemp]" min="0" max="0" step="1" required>
|
||||||
|
<small data-i18n>settings.ohProtection.lowTemp.note</small>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<small data-i18n>settings.ohProtection.desc</small>
|
||||||
|
</details>
|
||||||
|
|
||||||
|
<hr />
|
||||||
|
|
||||||
|
<details>
|
||||||
|
<summary><b data-i18n>settings.freezeProtection.title</b></summary>
|
||||||
|
|
||||||
|
<div class="grid">
|
||||||
|
<label>
|
||||||
|
<span data-i18n>settings.freezeProtection.lowTemp</span>
|
||||||
|
<input type="number" inputmode="numeric" name="heating[freezeProtection][lowTemp]" min="0" max="0" step="1" required>
|
||||||
|
</label>
|
||||||
|
|
||||||
|
<label>
|
||||||
|
<span data-i18n>settings.freezeProtection.thresholdTime</span>
|
||||||
|
<input type="number" inputmode="numeric" name="heating[freezeProtection][thresholdTime]" min="30" max="1800" step="1" required>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<small data-i18n>settings.freezeProtection.desc</small>
|
||||||
|
</details>
|
||||||
|
|
||||||
|
<br />
|
||||||
|
|
||||||
<button type="submit" data-i18n>button.save</button>
|
<button type="submit" data-i18n>button.save</button>
|
||||||
</form>
|
</form>
|
||||||
</div>
|
</div>
|
||||||
@@ -226,6 +276,35 @@
|
|||||||
</label>
|
</label>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
|
<label>
|
||||||
|
<span data-i18n>settings.maxModulation</span>
|
||||||
|
<input type="number" inputmode="numeric" name="dhw[maxModulation]" min="1" max="100" step="1" required>
|
||||||
|
</label>
|
||||||
|
|
||||||
|
<hr />
|
||||||
|
|
||||||
|
<details>
|
||||||
|
<summary><b data-i18n>settings.ohProtection.title</b></summary>
|
||||||
|
|
||||||
|
<div class="grid">
|
||||||
|
<label>
|
||||||
|
<span data-i18n>settings.ohProtection.highTemp.title</span>
|
||||||
|
<input type="number" inputmode="numeric" name="dhw[overheatProtection][highTemp]" min="0" max="0" step="1" required>
|
||||||
|
<small data-i18n>settings.ohProtection.highTemp.note</small>
|
||||||
|
</label>
|
||||||
|
|
||||||
|
<label>
|
||||||
|
<span data-i18n>settings.ohProtection.lowTemp.title</span>
|
||||||
|
<input type="number" inputmode="numeric" name="dhw[overheatProtection][lowTemp]" min="0" max="0" step="1" required>
|
||||||
|
<small data-i18n>settings.ohProtection.lowTemp.note</small>
|
||||||
|
</label>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<small data-i18n>settings.ohProtection.desc</small>
|
||||||
|
</details>
|
||||||
|
|
||||||
|
<br />
|
||||||
|
|
||||||
<button type="submit" data-i18n>button.save</button>
|
<button type="submit" data-i18n>button.save</button>
|
||||||
</form>
|
</form>
|
||||||
</div>
|
</div>
|
||||||
@@ -457,11 +536,6 @@
|
|||||||
<span data-i18n>settings.ot.flags</span>
|
<span data-i18n>settings.ot.flags</span>
|
||||||
<input type="number" inputmode="numeric" name="opentherm[flags]" min="0" max="255" step="1" required>
|
<input type="number" inputmode="numeric" name="opentherm[flags]" min="0" max="255" step="1" required>
|
||||||
</label>
|
</label>
|
||||||
|
|
||||||
<label>
|
|
||||||
<span data-i18n>settings.ot.maxMod</span>
|
|
||||||
<input type="number" inputmode="numeric" name="opentherm[maxModulation]" min="1" max="100" step="1" required>
|
|
||||||
</label>
|
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<div class="grid">
|
<div class="grid">
|
||||||
@@ -478,77 +552,107 @@
|
|||||||
</label>
|
</label>
|
||||||
</div>
|
</div>
|
||||||
|
|
||||||
<fieldset>
|
<details>
|
||||||
<legend data-i18n>settings.ot.options.desc</legend>
|
<summary><b data-i18n>settings.ot.options.title</b></summary>
|
||||||
|
|
||||||
<label>
|
<div>
|
||||||
<input type="checkbox" name="opentherm[options][dhwSupport]" value="true">
|
<fieldset>
|
||||||
<span data-i18n>settings.ot.options.dhwSupport</span>
|
<small data-i18n>settings.ot.options.desc</small>
|
||||||
</label>
|
</fieldset>
|
||||||
|
|
||||||
<label>
|
<fieldset>
|
||||||
<input type="checkbox" name="opentherm[options][coolingSupport]" value="true">
|
<label>
|
||||||
<span data-i18n>settings.ot.options.coolingSupport</span>
|
<input type="checkbox" name="opentherm[options][dhwSupport]" value="true">
|
||||||
</label>
|
<span data-i18n>settings.ot.options.dhwSupport</span>
|
||||||
|
</label>
|
||||||
|
|
||||||
<label>
|
<label>
|
||||||
<input type="checkbox" name="opentherm[options][summerWinterMode]" value="true">
|
<input type="checkbox" name="opentherm[options][coolingSupport]" value="true">
|
||||||
<span data-i18n>settings.ot.options.summerWinterMode</span>
|
<span data-i18n>settings.ot.options.coolingSupport</span>
|
||||||
</label>
|
</label>
|
||||||
|
|
||||||
<label>
|
<label>
|
||||||
<input type="checkbox" name="opentherm[options][heatingStateToSummerWinterMode]" value="true">
|
<input type="checkbox" name="opentherm[options][summerWinterMode]" value="true">
|
||||||
<span data-i18n>settings.ot.options.heatingStateToSummerWinterMode</span>
|
<span data-i18n>settings.ot.options.summerWinterMode</span>
|
||||||
</label>
|
</label>
|
||||||
|
|
||||||
<label>
|
<label>
|
||||||
<input type="checkbox" name="opentherm[options][ch2AlwaysEnabled]" value="true">
|
<input type="checkbox" name="opentherm[options][heatingStateToSummerWinterMode]" value="true">
|
||||||
<span data-i18n>settings.ot.options.ch2AlwaysEnabled</span>
|
<span data-i18n>settings.ot.options.heatingStateToSummerWinterMode</span>
|
||||||
</label>
|
</label>
|
||||||
|
|
||||||
<label>
|
<label>
|
||||||
<input type="checkbox" name="opentherm[options][heatingToCh2]" value="true">
|
<input type="checkbox" name="opentherm[options][ch2AlwaysEnabled]" value="true">
|
||||||
<span data-i18n>settings.ot.options.heatingToCh2</span>
|
<span data-i18n>settings.ot.options.ch2AlwaysEnabled</span>
|
||||||
</label>
|
</label>
|
||||||
|
|
||||||
<label>
|
<label>
|
||||||
<input type="checkbox" name="opentherm[options][dhwToCh2]" value="true">
|
<input type="checkbox" name="opentherm[options][heatingToCh2]" value="true">
|
||||||
<span data-i18n>settings.ot.options.dhwToCh2</span>
|
<span data-i18n>settings.ot.options.heatingToCh2</span>
|
||||||
</label>
|
</label>
|
||||||
|
|
||||||
<label>
|
<label>
|
||||||
<input type="checkbox" name="opentherm[options][dhwBlocking]" value="true">
|
<input type="checkbox" name="opentherm[options][dhwToCh2]" value="true">
|
||||||
<span data-i18n>settings.ot.options.dhwBlocking</span>
|
<span data-i18n>settings.ot.options.dhwToCh2</span>
|
||||||
</label>
|
</label>
|
||||||
|
|
||||||
<label>
|
<label>
|
||||||
<input type="checkbox" name="opentherm[options][modulationSyncWithHeating]" value="true">
|
<input type="checkbox" name="opentherm[options][dhwBlocking]" value="true">
|
||||||
<span data-i18n>settings.ot.options.modulationSyncWithHeating</span>
|
<span data-i18n>settings.ot.options.dhwBlocking</span>
|
||||||
</label>
|
</label>
|
||||||
|
|
||||||
<label>
|
<label>
|
||||||
<input type="checkbox" name="opentherm[options][maxTempSyncWithTargetTemp]" value="true">
|
<input type="checkbox" name="opentherm[options][dhwStateAsDhwBlocking]" value="true">
|
||||||
<span data-i18n>settings.ot.options.maxTempSyncWithTargetTemp</span>
|
<span data-i18n>settings.ot.options.dhwStateAsDhwBlocking</span>
|
||||||
</label>
|
</label>
|
||||||
|
|
||||||
<label>
|
<label>
|
||||||
<input type="checkbox" name="opentherm[options][getMinMaxTemp]" value="true">
|
<input type="checkbox" name="opentherm[options][maxTempSyncWithTargetTemp]" value="true">
|
||||||
<span data-i18n>settings.ot.options.getMinMaxTemp</span>
|
<span data-i18n>settings.ot.options.maxTempSyncWithTargetTemp</span>
|
||||||
</label>
|
</label>
|
||||||
|
|
||||||
<label>
|
<label>
|
||||||
<input type="checkbox" name="opentherm[options][immergasFix]" value="true">
|
<input type="checkbox" name="opentherm[options][getMinMaxTemp]" value="true">
|
||||||
<span data-i18n>settings.ot.options.immergasFix</span>
|
<span data-i18n>settings.ot.options.getMinMaxTemp</span>
|
||||||
</label>
|
</label>
|
||||||
|
|
||||||
<hr />
|
<label>
|
||||||
<label>
|
<input type="checkbox" name="opentherm[options][ignoreDiagState]" value="true">
|
||||||
<input type="checkbox" name="opentherm[options][nativeHeatingControl]" value="true">
|
<span data-i18n>settings.ot.options.ignoreDiagState</span>
|
||||||
<span data-i18n>settings.ot.nativeHeating.title</span><br />
|
</label>
|
||||||
<small data-i18n>settings.ot.nativeHeating.note</small>
|
|
||||||
</label>
|
|
||||||
</fieldset>
|
|
||||||
|
|
||||||
|
<label>
|
||||||
|
<input type="checkbox" name="opentherm[options][autoFaultReset]" value="true">
|
||||||
|
<span data-i18n>settings.ot.options.autoFaultReset</span>
|
||||||
|
</label>
|
||||||
|
|
||||||
|
<label>
|
||||||
|
<input type="checkbox" name="opentherm[options][autoDiagReset]" value="true">
|
||||||
|
<span data-i18n>settings.ot.options.autoDiagReset</span>
|
||||||
|
</label>
|
||||||
|
|
||||||
|
<label>
|
||||||
|
<input type="checkbox" name="opentherm[options][setDateAndTime]" value="true">
|
||||||
|
<span data-i18n>settings.ot.options.setDateAndTime</span>
|
||||||
|
</label>
|
||||||
|
|
||||||
|
<label>
|
||||||
|
<input type="checkbox" name="opentherm[options][immergasFix]" value="true">
|
||||||
|
<span data-i18n>settings.ot.options.immergasFix</span>
|
||||||
|
</label>
|
||||||
|
|
||||||
|
<hr />
|
||||||
|
|
||||||
|
<label>
|
||||||
|
<input type="checkbox" name="opentherm[options][nativeHeatingControl]" value="true">
|
||||||
|
<span data-i18n>settings.ot.nativeHeating.title</span><br />
|
||||||
|
<small data-i18n>settings.ot.nativeHeating.note</small>
|
||||||
|
</label>
|
||||||
|
</fieldset>
|
||||||
|
</div>
|
||||||
|
</details>
|
||||||
|
|
||||||
|
<br />
|
||||||
<button type="submit" data-i18n>button.save</button>
|
<button type="submit" data-i18n>button.save</button>
|
||||||
</form>
|
</form>
|
||||||
</div>
|
</div>
|
||||||
@@ -788,7 +892,6 @@
|
|||||||
setInputValue("[name='opentherm[rxLedGpio]']", data.opentherm.rxLedGpio < 255 ? data.opentherm.rxLedGpio : '');
|
setInputValue("[name='opentherm[rxLedGpio]']", data.opentherm.rxLedGpio < 255 ? data.opentherm.rxLedGpio : '');
|
||||||
setInputValue("[name='opentherm[memberId]']", data.opentherm.memberId);
|
setInputValue("[name='opentherm[memberId]']", data.opentherm.memberId);
|
||||||
setInputValue("[name='opentherm[flags]']", data.opentherm.flags);
|
setInputValue("[name='opentherm[flags]']", data.opentherm.flags);
|
||||||
setInputValue("[name='opentherm[maxModulation]']", data.opentherm.maxModulation);
|
|
||||||
setInputValue("[name='opentherm[minPower]']", data.opentherm.minPower);
|
setInputValue("[name='opentherm[minPower]']", data.opentherm.minPower);
|
||||||
setInputValue("[name='opentherm[maxPower]']", data.opentherm.maxPower);
|
setInputValue("[name='opentherm[maxPower]']", data.opentherm.maxPower);
|
||||||
setCheckboxValue("[name='opentherm[options][dhwSupport]']", data.opentherm.options.dhwSupport);
|
setCheckboxValue("[name='opentherm[options][dhwSupport]']", data.opentherm.options.dhwSupport);
|
||||||
@@ -799,9 +902,13 @@
|
|||||||
setCheckboxValue("[name='opentherm[options][heatingToCh2]']", data.opentherm.options.heatingToCh2);
|
setCheckboxValue("[name='opentherm[options][heatingToCh2]']", data.opentherm.options.heatingToCh2);
|
||||||
setCheckboxValue("[name='opentherm[options][dhwToCh2]']", data.opentherm.options.dhwToCh2);
|
setCheckboxValue("[name='opentherm[options][dhwToCh2]']", data.opentherm.options.dhwToCh2);
|
||||||
setCheckboxValue("[name='opentherm[options][dhwBlocking]']", data.opentherm.options.dhwBlocking);
|
setCheckboxValue("[name='opentherm[options][dhwBlocking]']", data.opentherm.options.dhwBlocking);
|
||||||
setCheckboxValue("[name='opentherm[options][modulationSyncWithHeating]']", data.opentherm.options.modulationSyncWithHeating);
|
setCheckboxValue("[name='opentherm[options][dhwStateAsDhwBlocking]']", data.opentherm.options.dhwStateAsDhwBlocking);
|
||||||
setCheckboxValue("[name='opentherm[options][maxTempSyncWithTargetTemp]']", data.opentherm.options.maxTempSyncWithTargetTemp);
|
setCheckboxValue("[name='opentherm[options][maxTempSyncWithTargetTemp]']", data.opentherm.options.maxTempSyncWithTargetTemp);
|
||||||
setCheckboxValue("[name='opentherm[options][getMinMaxTemp]']", data.opentherm.options.getMinMaxTemp);
|
setCheckboxValue("[name='opentherm[options][getMinMaxTemp]']", data.opentherm.options.getMinMaxTemp);
|
||||||
|
setCheckboxValue("[name='opentherm[options][ignoreDiagState]']", data.opentherm.options.ignoreDiagState);
|
||||||
|
setCheckboxValue("[name='opentherm[options][autoFaultReset]']", data.opentherm.options.autoFaultReset);
|
||||||
|
setCheckboxValue("[name='opentherm[options][autoDiagReset]']", data.opentherm.options.autoDiagReset);
|
||||||
|
setCheckboxValue("[name='opentherm[options][setDateAndTime]']", data.opentherm.options.setDateAndTime);
|
||||||
setCheckboxValue("[name='opentherm[options][nativeHeatingControl]']", data.opentherm.options.nativeHeatingControl);
|
setCheckboxValue("[name='opentherm[options][nativeHeatingControl]']", data.opentherm.options.nativeHeatingControl);
|
||||||
setCheckboxValue("[name='opentherm[options][immergasFix]']", data.opentherm.options.immergasFix);
|
setCheckboxValue("[name='opentherm[options][immergasFix]']", data.opentherm.options.immergasFix);
|
||||||
setBusy('#ot-settings-busy', '#ot-settings', false);
|
setBusy('#ot-settings-busy', '#ot-settings', false);
|
||||||
@@ -851,6 +958,20 @@
|
|||||||
});
|
});
|
||||||
setInputValue("[name='heating[hysteresis]']", data.heating.hysteresis);
|
setInputValue("[name='heating[hysteresis]']", data.heating.hysteresis);
|
||||||
setInputValue("[name='heating[turboFactor]']", data.heating.turboFactor);
|
setInputValue("[name='heating[turboFactor]']", data.heating.turboFactor);
|
||||||
|
setInputValue("[name='heating[maxModulation]']", data.heating.maxModulation);
|
||||||
|
setInputValue("[name='heating[overheatProtection][highTemp]']", data.heating.overheatProtection.highTemp, {
|
||||||
|
"min": 0,
|
||||||
|
"max": data.system.unitSystem == 0 ? 100 : 212
|
||||||
|
});
|
||||||
|
setInputValue("[name='heating[overheatProtection][lowTemp]']", data.heating.overheatProtection.lowTemp, {
|
||||||
|
"min": 0,
|
||||||
|
"max": data.system.unitSystem == 0 ? 99 : 211
|
||||||
|
});
|
||||||
|
setInputValue("[name='heating[freezeProtection][lowTemp]']", data.heating.freezeProtection.lowTemp, {
|
||||||
|
"min": data.system.unitSystem == 0 ? 1 : 34,
|
||||||
|
"max": data.system.unitSystem == 0 ? 30 : 86
|
||||||
|
});
|
||||||
|
setInputValue("[name='heating[freezeProtection][thresholdTime]']", data.heating.freezeProtection.thresholdTime);
|
||||||
setBusy('#heating-settings-busy', '#heating-settings', false);
|
setBusy('#heating-settings-busy', '#heating-settings', false);
|
||||||
|
|
||||||
// DHW
|
// DHW
|
||||||
@@ -862,14 +983,22 @@
|
|||||||
"min": data.system.unitSystem == 0 ? 1 : 33,
|
"min": data.system.unitSystem == 0 ? 1 : 33,
|
||||||
"max": data.system.unitSystem == 0 ? 100 : 212
|
"max": data.system.unitSystem == 0 ? 100 : 212
|
||||||
});
|
});
|
||||||
|
setInputValue("[name='dhw[maxModulation]']", data.dhw.maxModulation);
|
||||||
|
setInputValue("[name='dhw[overheatProtection][highTemp]']", data.dhw.overheatProtection.highTemp, {
|
||||||
|
"min": 0,
|
||||||
|
"max": data.system.unitSystem == 0 ? 100 : 212
|
||||||
|
});
|
||||||
|
setInputValue("[name='dhw[overheatProtection][lowTemp]']", data.dhw.overheatProtection.lowTemp, {
|
||||||
|
"min": 0,
|
||||||
|
"max": data.system.unitSystem == 0 ? 99 : 211
|
||||||
|
});
|
||||||
setBusy('#dhw-settings-busy', '#dhw-settings', false);
|
setBusy('#dhw-settings-busy', '#dhw-settings', false);
|
||||||
|
|
||||||
// Emergency mode
|
// Emergency mode
|
||||||
setInputValue("[name='emergency[tresholdTime]']", data.emergency.tresholdTime);
|
|
||||||
if (data.opentherm.options.nativeHeatingControl) {
|
if (data.opentherm.options.nativeHeatingControl) {
|
||||||
setInputValue("[name='emergency[target]']", data.emergency.target, {
|
setInputValue("[name='emergency[target]']", data.emergency.target, {
|
||||||
"min": data.system.unitSystem == 0 ? 5 : 41,
|
"min": data.system.unitSystem == 0 ? 5 : 41,
|
||||||
"max": data.system.unitSystem == 0 ? 30 : 86
|
"max": data.system.unitSystem == 0 ? 40 : 104
|
||||||
});
|
});
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
@@ -878,7 +1007,7 @@
|
|||||||
"max": data.heating.maxTemp,
|
"max": data.heating.maxTemp,
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
setInputValue("[name='emergency[tresholdTime]']", data.emergency.tresholdTime);
|
||||||
setBusy('#emergency-settings-busy', '#emergency-settings', false);
|
setBusy('#emergency-settings-busy', '#emergency-settings', false);
|
||||||
|
|
||||||
// Equitherm
|
// Equitherm
|
||||||
|
|||||||
@@ -21,6 +21,7 @@
|
|||||||
<li>
|
<li>
|
||||||
<select id="lang" aria-label="Lang">
|
<select id="lang" aria-label="Lang">
|
||||||
<option value="en" selected>EN</option>
|
<option value="en" selected>EN</option>
|
||||||
|
<option value="cn">CN</option>
|
||||||
<option value="it">IT</option>
|
<option value="it">IT</option>
|
||||||
<option value="ru">RU</option>
|
<option value="ru">RU</option>
|
||||||
</select>
|
</select>
|
||||||
|
|||||||
@@ -3,6 +3,10 @@
|
|||||||
--pico-block-spacing-vertical: calc(var(--pico-spacing) * 0.75);
|
--pico-block-spacing-vertical: calc(var(--pico-spacing) * 0.75);
|
||||||
--pico-block-spacing-horizontal: calc(var(--pico-spacing) * 0.75);
|
--pico-block-spacing-horizontal: calc(var(--pico-spacing) * 0.75);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
.logo {
|
||||||
|
font-size: 1.2rem;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@media (min-width: 768px) {
|
@media (min-width: 768px) {
|
||||||
@@ -10,6 +14,10 @@
|
|||||||
--pico-block-spacing-vertical: var(--pico-spacing);
|
--pico-block-spacing-vertical: var(--pico-spacing);
|
||||||
--pico-block-spacing-horizontal: var(--pico-spacing);
|
--pico-block-spacing-horizontal: var(--pico-spacing);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
.logo {
|
||||||
|
font-size: 1.25rem;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@media (min-width: 1024px) {
|
@media (min-width: 1024px) {
|
||||||
@@ -17,6 +25,10 @@
|
|||||||
--pico-block-spacing-vertical: calc(var(--pico-spacing) * 1.25);
|
--pico-block-spacing-vertical: calc(var(--pico-spacing) * 1.25);
|
||||||
--pico-block-spacing-horizontal: calc(var(--pico-spacing) * 1.25);
|
--pico-block-spacing-horizontal: calc(var(--pico-spacing) * 1.25);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
.logo {
|
||||||
|
font-size: 1.25rem;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@media (min-width: 1280px) {
|
@media (min-width: 1280px) {
|
||||||
@@ -25,6 +37,10 @@
|
|||||||
--pico-block-spacing-horizontal: calc(var(--pico-spacing) * 1.5);
|
--pico-block-spacing-horizontal: calc(var(--pico-spacing) * 1.5);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
.logo {
|
||||||
|
font-size: 1.3rem;
|
||||||
|
}
|
||||||
|
|
||||||
.container {
|
.container {
|
||||||
max-width: 1000px;
|
max-width: 1000px;
|
||||||
}
|
}
|
||||||
@@ -36,6 +52,10 @@
|
|||||||
--pico-block-spacing-horizontal: calc(var(--pico-spacing) * 1.75);
|
--pico-block-spacing-horizontal: calc(var(--pico-spacing) * 1.75);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
.logo {
|
||||||
|
font-size: 1.3rem;
|
||||||
|
}
|
||||||
|
|
||||||
.container {
|
.container {
|
||||||
max-width: 1000px;
|
max-width: 1000px;
|
||||||
}
|
}
|
||||||
@@ -111,7 +131,7 @@ tr.network:hover {
|
|||||||
border-radius: var(--pico-border-radius);
|
border-radius: var(--pico-border-radius);
|
||||||
color: var(--pico-code-kbd-color);
|
color: var(--pico-code-kbd-color);
|
||||||
font-weight: bolder;
|
font-weight: bolder;
|
||||||
font-size: 1.3rem;
|
/*font-size: 1.3rem;*/
|
||||||
font-family: var(--pico-font-family-monospace);
|
font-family: var(--pico-font-family-monospace);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -23,10 +23,15 @@ Import("env")
|
|||||||
platform = env.PioPlatform()
|
platform = env.PioPlatform()
|
||||||
|
|
||||||
import sys
|
import sys
|
||||||
|
import os
|
||||||
|
import subprocess
|
||||||
from os.path import join
|
from os.path import join
|
||||||
|
|
||||||
sys.path.append(join(platform.get_package_dir("tool-esptoolpy")))
|
def normalize_paths(cmd):
|
||||||
import esptool
|
for i, arg in enumerate(cmd):
|
||||||
|
if isinstance(arg, str) and '/' in arg:
|
||||||
|
cmd[i] = os.path.normpath(arg)
|
||||||
|
return cmd
|
||||||
|
|
||||||
def esp32_create_combined_bin(source, target, env):
|
def esp32_create_combined_bin(source, target, env):
|
||||||
print("Generating combined binary for serial flashing")
|
print("Generating combined binary for serial flashing")
|
||||||
@@ -39,26 +44,21 @@ def esp32_create_combined_bin(source, target, env):
|
|||||||
sections = env.subst(env.get("FLASH_EXTRA_IMAGES"))
|
sections = env.subst(env.get("FLASH_EXTRA_IMAGES"))
|
||||||
firmware_name = env.subst("$BUILD_DIR/${PROGNAME}.bin")
|
firmware_name = env.subst("$BUILD_DIR/${PROGNAME}.bin")
|
||||||
chip = env.get("BOARD_MCU")
|
chip = env.get("BOARD_MCU")
|
||||||
flash_size = env.BoardConfig().get("upload.flash_size")
|
flash_size = env.BoardConfig().get("upload.flash_size", "4MB")
|
||||||
flash_freq = env.BoardConfig().get("build.f_flash", '40m')
|
flash_mode = env["__get_board_flash_mode"](env)
|
||||||
flash_freq = flash_freq.replace('000000L', 'm')
|
flash_freq = env["__get_board_f_flash"](env)
|
||||||
flash_mode = env.BoardConfig().get("build.flash_mode", "dio")
|
|
||||||
memory_type = env.BoardConfig().get("build.arduino.memory_type", "qio_qspi")
|
|
||||||
if flash_mode == "qio" or flash_mode == "qout":
|
|
||||||
flash_mode = "dio"
|
|
||||||
if memory_type == "opi_opi" or memory_type == "opi_qspi":
|
|
||||||
flash_mode = "dout"
|
|
||||||
cmd = [
|
cmd = [
|
||||||
"--chip",
|
"--chip",
|
||||||
chip,
|
chip,
|
||||||
"merge_bin",
|
"merge-bin",
|
||||||
"-o",
|
"-o",
|
||||||
new_file_name,
|
new_file_name,
|
||||||
"--flash_mode",
|
"--flash-mode",
|
||||||
flash_mode,
|
flash_mode,
|
||||||
"--flash_freq",
|
"--flash-freq",
|
||||||
flash_freq,
|
flash_freq,
|
||||||
"--flash_size",
|
"--flash-size",
|
||||||
flash_size,
|
flash_size,
|
||||||
]
|
]
|
||||||
|
|
||||||
@@ -71,9 +71,12 @@ def esp32_create_combined_bin(source, target, env):
|
|||||||
print(f" - {hex(app_offset)} | {firmware_name}")
|
print(f" - {hex(app_offset)} | {firmware_name}")
|
||||||
cmd += [hex(app_offset), firmware_name]
|
cmd += [hex(app_offset), firmware_name]
|
||||||
|
|
||||||
print('Using esptool.py arguments: %s' % ' '.join(cmd))
|
# print('Using esptool.py arguments: %s' % ' '.join(cmd))
|
||||||
|
cmdline = [env.subst("$OBJCOPY")] + normalize_paths(cmd)
|
||||||
esptool.main(cmd)
|
print('Command Line: %s' % cmdline)
|
||||||
|
result = subprocess.run(cmdline, text=True, check=False, stdout=subprocess.DEVNULL)
|
||||||
|
if result.returncode != 0:
|
||||||
|
print(f"esptool create firmware failed with exit code: {result.returncode}")
|
||||||
|
|
||||||
|
|
||||||
env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", esp32_create_combined_bin)
|
env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", esp32_create_combined_bin)
|
||||||
|
|||||||
Reference in New Issue
Block a user