Skip to content

Commit

Permalink
Merge pull request #310 from IgorYbema/main
Browse files Browse the repository at this point in the history
Release HeishaMon v3.1
  • Loading branch information
Egyras authored Jan 16, 2023
2 parents 98a738d + e4955ce commit 57e8567
Show file tree
Hide file tree
Showing 27 changed files with 554 additions and 154 deletions.
11 changes: 8 additions & 3 deletions .github/workflows/main.yml
Original file line number Diff line number Diff line change
Expand Up @@ -2,19 +2,24 @@ name: Build binary

on: [push, pull_request]

env:
ARDUINO_BOARD_MANAGER_ADDITIONAL_URLS: http://arduino.esp8266.com/stable/package_esp8266com_index.json

jobs:
build:
runs-on: windows-latest

steps:
- name: Checkout
uses: actions/checkout@v2
uses: actions/checkout@v3

- name: Setup Arduino CLI
uses: arduino/setup-arduino-cli@v1
uses: arduino/setup-arduino-cli@v1.1.1

- name: Install platform
run: arduino-cli core install esp8266:esp8266 --additional-urls https://arduino.esp8266.com/stable/package_esp8266com_index.json -v
run: |
arduino-cli core update-index
arduino-cli core install esp8266:esp8266
- name: Install dependencies
run: arduino-cli lib install ringbuffer pubsubclient doubleresetdetect arduinojson dallastemperature onewire WebSockets
Expand Down
6 changes: 6 additions & 0 deletions HeatPumpType.md
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,12 @@ Assuming that bytes from #129 to #138 are unique for each model of Aquarea heat
|20 | C2 D3 0B 34 65 B2 D3 0B 95 65 | Monoblock | WH-MDC07J3E5 | Monoblock | 7 | 1ph | HP |
|21 | C2 D3 0B 35 65 B2 D3 0B 96 65 | Monoblock | WH-MDC09J3E5 | Monoblock | 9 | 1ph | HP |
|22 | 62 D2 0B 41 54 32 D2 0C 45 55 | WH-SDC0305J3E5 | WH-UD05JE5 | KIT-WC05J3E5 | 5 | 1ph | HP |
|23 | 32 D4 0B 87 84 73 90 0C 84 84 | Monoblock | WH-MXC09J3E8 | Monoblock | 9 | 3ph | T-CAP |
|24 | 32 D4 0B 88 84 73 90 0C 85 84 | MonoBlock | WH-MXC12J9E8 | Monoblock | 12 | 3ph | T-CAP |
|25 | E2 CF 0B 75 09 12 D0 0C 06 11 | WH-ADC1216H6E5 | WH-UD12HE5 | KIT-ADC12HE5 | 12 | 1ph | T-CAP |
|26 | 42 D4 0B 83 71 42 D2 0C 46 55 | WH-ADC0309J3E5C | WH-UD07JE5 | KIT-ADC07JE5C | 7 | 1ph | HP - All-In-One Compact |
|27 | C2 D3 0C 34 65 B2 D3 0B 95 65 | Monoblock | WH-MDC07J3E5 | Monoblock | 7 | 1ph | HP (new version?) |
|28 | C2 D3 0C 33 65 B2 D3 0B 94 65 | Monoblcok | WH-MDC05J3E5 | Monoblock | 5 | 1ph | HP (new version? |

All bytes are used for Heat Pump model identification in the code.

Expand Down
99 changes: 59 additions & 40 deletions HeishaMon/HeishaMon.ino
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ static int uploadpercentage = 0;
char data[MAXDATASIZE] = { '\0' };
byte data_length = 0;

// store actual data
// store actual data
String openTherm[2];
char actData[DATASIZE] = { '\0' };
#define OPTDATASIZE 20
Expand Down Expand Up @@ -117,7 +117,7 @@ void check_wifi()
if ((WiFi.status() != WL_CONNECTED) && (WiFi.localIP())) {
// special case where it seems that we are not connect but we do have working IP (causing the -1% wifi signal), do a reset.
log_message((char *)"Weird case, WiFi seems disconnected but is not. Resetting WiFi!");
setupWifi(&heishamonSettings);
setupWifi(&heishamonSettings);
} else if ((WiFi.status() != WL_CONNECTED) || (!WiFi.localIP())) {
/*
if we are not connected to an AP
Expand Down Expand Up @@ -231,8 +231,8 @@ void mqtt_reconnect()
void log_message(const __FlashStringHelper *msg) {
PGM_P p = (PGM_P)msg;
int len = strlen_P((const char *)p);
char *str = (char *)MALLOC(len+1);
if(str == NULL) {
char *str = (char *)MALLOC(len + 1);
if (str == NULL) {
OUT_OF_MEMORY
}
strcpy_P(str, p);
Expand Down Expand Up @@ -307,7 +307,7 @@ bool readSerial()
{
int len = 0;
while ((Serial.available()) && (len < MAXDATASIZE)) {
data[data_length+len] = Serial.read(); //read available data and place it after the last received data
data[data_length + len] = Serial.read(); //read available data and place it after the last received data
len++;
if (data[0] != 113) { //wrong header received!
log_message(F("Received bad header. Ignoring this data!"));
Expand All @@ -320,7 +320,7 @@ bool readSerial()

if ((len > 0) && (data_length == 0 )) totalreads++; //this is the start of a new read
data_length += len;

if (data_length > 1) { //should have received length part of header now

if ((data_length > (data[1] + 3)) || (data_length >= MAXDATASIZE) ) {
Expand Down Expand Up @@ -534,7 +534,7 @@ int8_t webserver_cb(struct webserver_t *client, void *dat) {
} else if (strcmp_P((char *)dat, PSTR("/factoryreset")) == 0) {
client->route = 90;
} else if (strcmp_P((char *)dat, PSTR("/command")) == 0) {
if((client->userdata = malloc(1)) == NULL) {
if ((client->userdata = malloc(1)) == NULL) {
Serial1.printf(PSTR("Out of memory %s:#%d\n"), __FUNCTION__, __LINE__);
ESP.restart();
exit(-1);
Expand Down Expand Up @@ -701,7 +701,7 @@ int8_t webserver_cb(struct webserver_t *client, void *dat) {
case WEBSERVER_CLIENT_WRITE: {
switch (client->route) {
case 0: {
if(client->content == 0) {
if (client->content == 0) {
webserver_send(client, 404, (char *)"text/plain", 13);
webserver_send_content_P(client, PSTR("404 Not found"), 13);
}
Expand Down Expand Up @@ -745,6 +745,12 @@ int8_t webserver_cb(struct webserver_t *client, void *dat) {
} break;
case 110: {
int ret = saveSettings(client, &heishamonSettings);
if (heishamonSettings.listenonly) {
//make sure we disable TX to heatpump-RX using the mosfet so this line is floating and will not disturb cz-taw1
digitalWrite(5, LOW);
} else {
digitalWrite(5, HIGH);
}
switch (client->route) {
case 111: {
return settingsNewPassword(client, &heishamonSettings);
Expand Down Expand Up @@ -825,7 +831,7 @@ int8_t webserver_cb(struct webserver_t *client, void *dat) {
return -1;
} break;
default: {
if(client->route != 0) {
if (client->route != 0) {
header->ptr += sprintf_P((char *)header->buffer, PSTR("Access-Control-Allow-Origin: *"));
}
} break;
Expand All @@ -835,33 +841,33 @@ int8_t webserver_cb(struct webserver_t *client, void *dat) {
case WEBSERVER_CLIENT_CLOSE: {
switch (client->route) {
case 100: {
if (client->userdata != NULL) {
free(client->userdata);
}
} break;
if (client->userdata != NULL) {
free(client->userdata);
}
} break;
case 110: {
struct websettings_t *tmp = NULL;
while (client->userdata) {
tmp = (struct websettings_t *)client->userdata;
client->userdata = ((struct websettings_t *)(client->userdata))->next;
free(tmp);
}
} break;
struct websettings_t *tmp = NULL;
while (client->userdata) {
tmp = (struct websettings_t *)client->userdata;
client->userdata = ((struct websettings_t *)(client->userdata))->next;
free(tmp);
}
} break;
case 160:
case 170: {
if (client->userdata != NULL) {
File *f = (File *)client->userdata;
if (f) {
if (*f) {
f->close();
if (client->userdata != NULL) {
File *f = (File *)client->userdata;
if (f) {
if (*f) {
f->close();
}
delete f;
}
delete f;
}
}
} break;
} break;
}
client->userdata = NULL;
} break;
} break;
default: {
return 0;
} break;
Expand Down Expand Up @@ -928,9 +934,21 @@ void switchSerial() {

setupGPIO(heishamonSettings.gpioSettings); //switch extra GPIOs to configured mode

//enable gpio15 after boot using gpio5 (D1) which enables the level shifter for the tx to panasonic
//mosfet output enable
pinMode(5, OUTPUT);
digitalWrite(5, HIGH);

//try to detect if cz-taw1 is connected in parallel
if (!heishamonSettings.listenonly) {
if (Serial.available() > 0) {
log_message(F("There is data on the line without asking for it. Switching to listen only mode."));
heishamonSettings.listenonly = true;
}
else {
//enable gpio15 after boot using gpio5 (D1) which enables the level shifter for the tx to panasonic
//do not enable if listen only to keep the line floating
digitalWrite(5, HIGH);
}
}
}

void setupMqtt() {
Expand All @@ -941,6 +959,8 @@ void setupMqtt() {
}

void setupConditionals() {
//send_initial_query(); //maybe necessary but for now disable. CZ-TAW1 sends this query on boot

//load optional PCB data from flash
if (heishamonSettings.optionalPCB) {
if (loadOptionalPCB(optionalPCBQuery, OPTIONALPCBQUERYSIZE)) {
Expand All @@ -957,10 +977,12 @@ void setupConditionals() {
//these two after optional pcb because it needs to send a datagram fast after boot
if (heishamonSettings.use_1wire) initDallasSensors(log_message, heishamonSettings.updataAllDallasTime, heishamonSettings.waitDallasTime, heishamonSettings.dallasResolution);
if (heishamonSettings.use_s0) initS0Sensors(heishamonSettings.s0Settings);


}

void timer_cb(int nr) {
if(nr > 0) {
if (nr > 0) {
rules_timer_cb(nr);
} else {
switch (nr) {
Expand All @@ -977,12 +999,12 @@ void timer_cb(int nr) {
setupWifi(&heishamonSettings);
} break;
case -4: {
if(rules_parse("/rules.new") == -1) {
if (rules_parse("/rules.new") == -1) {
logprintln_P(F("new ruleset failed to parse, using previous ruleset"));
rules_parse("/rules.txt");
} else {
logprintln_P(F("new ruleset successfully parsed"));
if(LittleFS.begin()) {
if (LittleFS.begin()) {
LittleFS.rename("/rules.new", "/rules.txt");
}
}
Expand Down Expand Up @@ -1034,18 +1056,15 @@ void setup() {
dnsServer.setErrorReplyCode(DNSReplyCode::NoError);
dnsServer.start(DNS_PORT, "*", apIP);

//maybe necessary but for now disable. CZ-TAW1 sends this query on boot
//if (!heishamonSettings.listenonly) send_initial_query();

rst_info *resetInfo = ESP.getResetInfoPtr();
Serial1.printf(PSTR("Reset reason: %d, exception cause: %d\n"), resetInfo->reason, resetInfo->exccause);

if(resetInfo->reason > 0 && resetInfo->reason < 4) {
if(LittleFS.begin()) {
if (resetInfo->reason > 0 && resetInfo->reason < 4) {
if (LittleFS.begin()) {
LittleFS.rename("/rules.txt", "/rules.old");
}
rules_setup();
if(LittleFS.begin()) {
if (LittleFS.begin()) {
LittleFS.rename("/rules.old", "/rules.txt");
}
} else {
Expand Down
68 changes: 68 additions & 0 deletions HeishaMon/commands.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -595,6 +595,74 @@ unsigned int set_main_schedule(char *msg, unsigned char *cmd, char *log_msg) {
return sizeof(panasonicSendQuery);
}

unsigned int set_alt_external_sensor(char *msg, unsigned char *cmd, char *log_msg) {

String set_alt_string(msg);

byte set_alt = 16;
if ( set_alt_string.toInt() == 1 ) {
set_alt = 32;
}

{
char tmp[256] = { 0 };
snprintf_P(tmp, 255, PSTR("set alternative external sensor to %d"), ((set_alt / 16) - 1) );
memcpy(log_msg, tmp, sizeof(tmp));
}

{
memcpy_P(cmd, panasonicSendQuery, sizeof(panasonicSendQuery));
cmd[20] = set_alt;
}

return sizeof(panasonicSendQuery);
}

unsigned int set_external_pad_heater(char *msg, unsigned char *cmd, char *log_msg) {

String set_pad_string(msg);

byte set_pad = 16;
if ( set_pad_string.toInt() == 1 ) {
set_pad = 32;
}
if ( set_pad_string.toInt() == 2 ) {
set_pad = 48;
}
{
char tmp[256] = { 0 };
snprintf_P(tmp, 255, PSTR("set external pad heater to %d"), ((set_pad / 16) - 1) );
memcpy(log_msg, tmp, sizeof(tmp));
}

{
memcpy_P(cmd, panasonicSendQuery, sizeof(panasonicSendQuery));
cmd[25] = set_pad;
}

return sizeof(panasonicSendQuery);
}

unsigned int set_buffer_delta(char *msg, unsigned char *cmd, char *log_msg) {

String set_temperature_string(msg);

byte request_temp = set_temperature_string.toInt() + 128;

{
char tmp[256] = { 0 };
snprintf_P(tmp, 255, PSTR("set buffer tank delta to %d"), request_temp - 128 );
memcpy(log_msg, tmp, sizeof(tmp));
}

{
memcpy_P(cmd, panasonicSendQuery, sizeof(panasonicSendQuery));
cmd[59] = request_temp;
}

return sizeof(panasonicSendQuery);
}

//start of optional pcb commands
unsigned int set_byte_6(int val, int base, int bit, char *log_msg, const char *func) {
unsigned char hex = (optionalPCBQuery[6] & ~(base << bit)) | (val << bit);
Expand Down
6 changes: 6 additions & 0 deletions HeishaMon/commands.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,9 @@ unsigned int set_heater_delay_time(char *msg, unsigned char *cmd, char *log_msg)
unsigned int set_heater_start_delta(char *msg, unsigned char *cmd, char *log_msg);
unsigned int set_heater_stop_delta(char *msg, unsigned char *cmd, char *log_msg);
unsigned int set_main_schedule(char *msg, unsigned char *cmd, char *log_msg);
unsigned int set_alt_external_sensor(char *msg, unsigned char *cmd, char *log_msg);
unsigned int set_external_pad_heater(char *msg, unsigned char *cmd, char *log_msg);
unsigned int set_buffer_delta(char *msg, unsigned char *cmd, char *log_msg);

//optional pcb commands
unsigned int set_heat_cool_mode(char *msg, char *log_msg);
Expand Down Expand Up @@ -117,6 +120,9 @@ const cmdStruct commands[] PROGMEM = {
{ "SetHeaterStartDelta", set_heater_start_delta },
{ "SetHeaterStopDelta", set_heater_stop_delta },
{ "SetMainSchedule", set_main_schedule },
{ "SetAltExternalSensor", set_alt_external_sensor },
{ "SetExternalPadHeater", set_external_pad_heater },
{ "SetBufferDelta", set_buffer_delta },
};

struct optCmdStruct{
Expand Down
Loading

0 comments on commit 57e8567

Please sign in to comment.