Skip to content

Commit

Permalink
Merge pull request #397 from IgorYbema/main
Browse files Browse the repository at this point in the history
release v3.2.3
  • Loading branch information
Egyras authored Nov 3, 2023
2 parents 34e9965 + 1137f37 commit f15a0fe
Show file tree
Hide file tree
Showing 17 changed files with 165 additions and 61 deletions.
16 changes: 11 additions & 5 deletions HeishaMon/HeishaMon.ino
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@

#define LWIP_INTERNAL

#include <ESP8266WiFi.h>
Expand Down Expand Up @@ -1013,6 +1014,9 @@ void timer_cb(int nr) {
case -1: {
LittleFS.begin();
LittleFS.format();
//create first boot file
File startupFile = LittleFS.open("/heishamon", "w");
startupFile.close();
WiFi.disconnect(true);
timerqueue_insert(1, 0, -2);
} break;
Expand Down Expand Up @@ -1142,11 +1146,13 @@ void send_panasonic_query() {
send_command(panasonicQuery, PANASONICQUERYSIZE);
panasonicQuery[3] = 0x10; //setting 4th back to 0x10 for normal data request next time
} else if (!extraDataBlockChecked) {
extraDataBlockChecked = true;
log_message(_F("Checking if connected heatpump has extra data"));
panasonicQuery[3] = 0x21;
send_command(panasonicQuery, PANASONICQUERYSIZE);
panasonicQuery[3] = 0x10;
if ((actData[0] == 0x71) && (actData[193] == 0) ) { //do we have data but 0 value in heat consumptiom power, then assume K or L series
extraDataBlockChecked = true;
log_message(_F("Checking if connected heatpump has extra data"));
panasonicQuery[3] = 0x21;
send_command(panasonicQuery, PANASONICQUERYSIZE);
panasonicQuery[3] = 0x10;
}
}
}

Expand Down
19 changes: 16 additions & 3 deletions HeishaMon/HeishaOT.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ struct heishaOTDataStruct_t heishaOTDataStruct[] = {
{ "flameState", TBOOL, { .b = false }, 1 }, //provides current flame state to thermostat
{ "chState", TBOOL, { .b = false }, 1 }, //provides if boiler is in centrale heating state
{ "dhwState", TBOOL, { .b = false }, 1 }, //provides if boiler is in dhw heating state
{ "roomSetOverride", TFLOAT, { .f = 0 }, 1 }, //provides a room setpoint override ID9 (not implemented completly in heishamon)
{ NULL, 0, 0, 0 }
};

Expand Down Expand Up @@ -225,7 +226,7 @@ void processOTRequest(unsigned long request, OpenThermResponseStatus status) {
unsigned long data = ot.temperatureToData(getOTStructMember(_F("inletTemp"))->value.f);
otResponse = ot.buildResponse(OpenThermMessageType::READ_ACK, OpenThermMessageID::Tret, data);
} else {
otResponse = ot.buildResponse(OpenThermMessageType::DATA_INVALID, OpenThermMessageID::Tboiler, request & 0xffff);
otResponse = ot.buildResponse(OpenThermMessageType::DATA_INVALID, OpenThermMessageID::Tret, request & 0xffff);
}
} break;
case OpenThermMessageID::Tdhw: {
Expand All @@ -234,7 +235,7 @@ void processOTRequest(unsigned long request, OpenThermResponseStatus status) {
unsigned long data = ot.temperatureToData(getOTStructMember(_F("dhwTemp"))->value.f);
otResponse = ot.buildResponse(OpenThermMessageType::READ_ACK, OpenThermMessageID::Tdhw, data);
} else {
otResponse = ot.buildResponse(OpenThermMessageType::DATA_INVALID, OpenThermMessageID::Tboiler, request & 0xffff);
otResponse = ot.buildResponse(OpenThermMessageType::DATA_INVALID, OpenThermMessageID::Tdhw, request & 0xffff);
}
} break;
case OpenThermMessageID::Toutside: {
Expand All @@ -244,9 +245,21 @@ void processOTRequest(unsigned long request, OpenThermResponseStatus status) {
otResponse = ot.buildResponse(OpenThermMessageType::READ_ACK, OpenThermMessageID::Toutside, data);

} else {
otResponse = ot.buildResponse(OpenThermMessageType::DATA_INVALID, OpenThermMessageID::Tboiler, request & 0xffff);
otResponse = ot.buildResponse(OpenThermMessageType::DATA_INVALID, OpenThermMessageID::Toutside, request & 0xffff);
}
} break;
case OpenThermMessageID::TrOverride: {
log_message(_F("OpenTherm: Received read room set override temp"));
if (getOTStructMember(_F("roomSetOverride"))->value.f > -99) {
unsigned long data = ot.temperatureToData(getOTStructMember(_F("roomSetOverride"))->value.f);
otResponse = ot.buildResponse(OpenThermMessageType::READ_ACK, OpenThermMessageID::TrOverride, data);

} else {
otResponse = ot.buildResponse(OpenThermMessageType::DATA_INVALID, OpenThermMessageID::TrOverride, request & 0xffff);
}
} break;


/*
case OpenThermMessageID::ASFflags: {
log_message(_F("OpenTherm: Received read ASF flags"));
Expand Down
9 changes: 2 additions & 7 deletions HeishaMon/decode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -313,20 +313,15 @@ void decode_heatpump_data_extra(char* data, char* actDataExtra, PubSubClient &mq
for (unsigned int Topic_Number = 0 ; Topic_Number < NUMBER_OF_TOPICS_EXTRA ; Topic_Number++) {
String Topic_Value;
Topic_Value = getDataValueExtra(data, Topic_Number);
{
char log_msg[256];
sprintf_P(log_msg, PSTR("testing XTOP%d %s: %s"), Topic_Number, xtopics[Topic_Number], Topic_Value.c_str());
log_message(log_msg);
}


if ((updatenow) || ( getDataValueExtra(actDataExtra, Topic_Number) != Topic_Value )) {
char log_msg[256];
char mqtt_topic[256];
sprintf_P(log_msg, PSTR("received XTOP%d %s: %s"), Topic_Number, xtopics[Topic_Number], Topic_Value.c_str());
log_message(log_msg);
sprintf_P(mqtt_topic, PSTR("%s/%s/%s"), mqtt_topic_base, mqtt_topic_xvalues, xtopics[Topic_Number]);
mqtt_client.publish(mqtt_topic, Topic_Value.c_str(), MQTT_RETAIN_VALUES);
rules_event_cb(_F("^"),xtopics[Topic_Number]);
rules_event_cb(_F("@"), xtopics[Topic_Number]);
}
}
}
Expand Down
13 changes: 7 additions & 6 deletions HeishaMon/decode.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ void resetlastalldatatime();

String getDataValue(char* data, unsigned int Topic_Number);
String getDataValueExtra(char* data, unsigned int Topic_Number);
String getOptDataValue(char* data, unsigned int Topic_Number);
void decode_heatpump_data(char* data, char* actData, PubSubClient &mqtt_client, void (*log_message)(char*), char* mqtt_topic_base, unsigned int updateAllTime);
void decode_heatpump_data_extra(char* data, char* actDataExtra, PubSubClient &mqtt_client, void (*log_message)(char*), char* mqtt_topic_base, unsigned int updateAllTime);
void decode_optional_heatpump_data(char* data, char* actOptDat, PubSubClient &mqtt_client, void (*log_message)(char*), char* mqtt_topic_base, unsigned int updateAllTime);
Expand Down Expand Up @@ -136,12 +137,12 @@ static const char optTopics[][20] PROGMEM = {
};

static const char xtopics[][MAX_TOPIC_LEN] PROGMEM = {
"Heat_Power_Consumption", //XTOP0
"Cool_Power_Consumption", //XTOP1
"DHW_Power_Consumption", //XTOP2
"Heat_Power_Production", //XTOP3
"Cool_Power_Production", //XTOP4
"DHW_Power_Production", //XTOP5
"Heat_Power_Consumption_Extra", //XTOP0
"Cool_Power_Consumption_Extra", //XTOP1
"DHW_Power_Consumption_Extra", //XTOP2
"Heat_Power_Production_Extra", //XTOP3
"Cool_Power_Production_Extra", //XTOP4
"DHW_Power_Production_Extra", //XTOP5
};

static const byte xtopicBytes[] PROGMEM = { //can store the index as byte (8-bit unsigned humber) as there aren't more then 255 bytes (actually only 203 bytes) to decode
Expand Down
135 changes: 111 additions & 24 deletions HeishaMon/rules.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,13 +27,15 @@
#include "commands.h"

#define MAXCOMMANDSINBUFFER 10
#define OPTDATASIZE 20

bool send_command(byte* command, int length);

extern int dallasDevicecount;
extern dallasDataStruct *actDallasData;
extern settingsStruct heishamonSettings;
extern char actData[DATASIZE];
extern char actOptData[OPTDATASIZE];
extern char actDataExtra[DATASIZE];
extern String openTherm[2];
static uint8_t parsing = 0;
Expand Down Expand Up @@ -173,7 +175,6 @@ static int is_variable(char *text, unsigned int *pos, unsigned int size) {
break;
}
}

if(match == 0) {
int nrtopics = sizeof(topics)/sizeof(topics[0]);
for(x=0;x<nrtopics;x++) {
Expand All @@ -187,6 +188,32 @@ static int is_variable(char *text, unsigned int *pos, unsigned int size) {
}
}
}
if(match == 0) {
int nrtopics = sizeof(optTopics)/sizeof(optTopics[0]);
for(x=0;x<nrtopics;x++) {
char cpy[MAX_TOPIC_LEN];
memcpy_P(&cpy, optTopics[x], MAX_TOPIC_LEN);
size_t len = strlen(cpy);
if(size-1 == len && strnicmp(&text[(*pos)+1], cpy, len) == 0) {
i = len+1;
match = 1;
break;
}
}
}
if(match == 0) {
int nrtopics = sizeof(xtopics)/sizeof(xtopics[0]);
for(x=0;x<nrtopics;x++) {
char cpy[MAX_TOPIC_LEN];
memcpy_P(&cpy, xtopics[x], MAX_TOPIC_LEN);
size_t len = strlen(cpy);
if(size-1 == len && strnicmp(&text[(*pos)+1], cpy, len) == 0) {
i = len+1;
match = 1;
break;
}
}
}
if(match == 0) {
return -1;
}
Expand Down Expand Up @@ -227,27 +254,56 @@ static int is_event(char *text, unsigned int *pos, unsigned int size) {
}
}

int nroptcommands = sizeof(optionalCommands)/sizeof(optionalCommands[0]);
for(x=0;x<nroptcommands;x++) {
optCmdStruct cmd;
memcpy_P(&cmd, &optionalCommands[x], sizeof(cmd));
size_t len = strlen(cmd.name);
if(size-1 == len && strnicmp(&text[(*pos)+1], cmd.name, len) == 0) {
i = len+1;
match = 1;
break;
if(match == 0) {
int nroptcommands = sizeof(optionalCommands)/sizeof(optionalCommands[0]);
for(x=0;x<nroptcommands;x++) {
optCmdStruct cmd;
memcpy_P(&cmd, &optionalCommands[x], sizeof(cmd));
size_t len = strlen(cmd.name);
if(size-1 == len && strnicmp(&text[(*pos)+1], cmd.name, len) == 0) {
i = len+1;
match = 1;
break;
}
}
}

int nrtopics = sizeof(topics)/sizeof(topics[0]);
for(x=0;x<nrtopics;x++) {
size_t len = strlen_P(topics[x]);
char cpy[len];
memcpy_P(&cpy, &topics[x], len);
if(size-1 == len && strnicmp(&text[(*pos)+1], cpy, len) == 0) {
i = len+1;
match = 1;
break;
if(match == 0) {
int nrtopics = sizeof(topics)/sizeof(topics[0]);
for(x=0;x<nrtopics;x++) {
size_t len = strlen_P(topics[x]);
char cpy[len];
memcpy_P(&cpy, &topics[x], len);
if(size-1 == len && strnicmp(&text[(*pos)+1], cpy, len) == 0) {
i = len+1;
match = 1;
break;
}
}
}
if(match == 0) {
int nrtopics = sizeof(optTopics)/sizeof(optTopics[0]);
for(x=0;x<nrtopics;x++) {
size_t len = strlen_P(optTopics[x]);
char cpy[len];
memcpy_P(&cpy, &optTopics[x], len);
if(size-1 == len && strnicmp(&text[(*pos)+1], cpy, len) == 0) {
i = len+1;
match = 1;
break;
}
}
}
if(match == 0) {
int nrtopics = sizeof(xtopics)/sizeof(xtopics[0]);
for(x=0;x<nrtopics;x++) {
size_t len = strlen_P(xtopics[x]);
char cpy[len];
memcpy_P(&cpy, &xtopics[x], len);
if(size-1 == len && strnicmp(&text[(*pos)+1], cpy, len) == 0) {
i = len+1;
match = 1;
break;
}
}
}
if(match == 0) {
Expand Down Expand Up @@ -548,11 +604,42 @@ static unsigned char *vm_value_get(struct rules_t *obj, uint16_t token) {
}
}
}
}
if(node->token[0] == '&') {
for(i=0;i<NUMBER_OF_TOPICS_EXTRA;i++) {
for(i=0;i<NUMBER_OF_OPT_TOPICS;i++) {
char cpy[MAX_TOPIC_LEN];
memcpy_P(&cpy, topics[i], MAX_TOPIC_LEN);
if(stricmp(cpy, (char *)&node->token[1]) == 0) {
String dataValue = actOptData[0] == '\0' ? "" : getOptDataValue(actOptData, i);
char *str = (char *)dataValue.c_str();
if(strlen(str) == 0) {
memset(&vnull, 0, sizeof(struct vm_vnull_t));
vnull.type = VNULL;
vnull.ret = token;

return (unsigned char *)&vnull;
} else {
float var = atof(str);
float nr = 0;

// mosquitto_publish
if(modff(var, &nr) == 0) {
memset(&vinteger, 0, sizeof(struct vm_vinteger_t));
vinteger.type = VINTEGER;
vinteger.value = (int)var;

return (unsigned char *)&vinteger;
} else {
memset(&vfloat, 0, sizeof(struct vm_vfloat_t));
vfloat.type = VFLOAT;
vfloat.value = var;

return (unsigned char *)&vfloat;
}
}
}
}
for(i=0;i<NUMBER_OF_TOPICS_EXTRA;i++) {
char cpy[MAX_TOPIC_LEN];
memcpy_P(&cpy, xtopics[i], MAX_TOPIC_LEN);
if(stricmp(cpy, (char *)&node->token[1]) == 0) {
String dataValue = actDataExtra[0] == '\0' ? "" : getDataValueExtra(actDataExtra, i);
char *str = (char *)dataValue.c_str();
Expand Down Expand Up @@ -583,7 +670,7 @@ static unsigned char *vm_value_get(struct rules_t *obj, uint16_t token) {
}
}
}
}
}
if(node->token[0] == '%') {
if(stricmp((char *)&node->token[1], "hour") == 0) {
time_t now = time(NULL);
Expand Down
2 changes: 1 addition & 1 deletion HeishaMon/version.h
Original file line number Diff line number Diff line change
@@ -1 +1 @@
static const char* heishamon_version = "3.2";
static const char* heishamon_version = "3.2.3";
6 changes: 3 additions & 3 deletions HeishaMon/webfunctions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1159,7 +1159,7 @@ int handleJsonOutput(struct webserver_t *client, char* actData, char* actDataExt
client->content--; // The webserver also increases by 1
} else if ((client->content - NUMBER_OF_TOPICS - 1) < extraTopics) {
if (client->content == NUMBER_OF_TOPICS + 1) {
webserver_send_content_P(client, PSTR("],\"heatpump extra\":["), 20);
webserver_send_content_P(client, PSTR("],\"heatpump extra\":["), 20);
}
for (uint8_t topic = (client->content - NUMBER_OF_TOPICS - 1); topic < extraTopics && topic < (client->content - NUMBER_OF_TOPICS + 4) ; topic++) {

Expand Down Expand Up @@ -1260,11 +1260,11 @@ int showRules(struct webserver_t *client) {

if (len1 > 0) {
webserver_send_content(client, content, len1);
if (len1 < BUFFER_SIZE) {
if (len1 < BUFFER_SIZE || client->content * BUFFER_SIZE == len) {
if (f) {
if (*f) {
f->close();
}
}
delete f;
}
client->userdata = NULL;
Expand Down
2 changes: 1 addition & 1 deletion HeishaMon/webfunctions.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ struct settingsStruct {
bool logMqtt = false; //log to mqtt from start
bool logHexdump = false; //log hexdump from start
bool logSerial1 = true; //log to serial1 (gpio2) from start
bool opentherm = true; //opentherm enable flag, current default true for opentherm build
bool opentherm = false; //opentherm enable flag

s0SettingsStruct s0Settings[NUM_S0_COUNTERS];
gpioSettingsStruct gpioSettings;
Expand Down
16 changes: 9 additions & 7 deletions MQTT-Topics.md
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,8 @@ TOP11 | main/Operations_Hours | Heatpump operating time (Hour)
TOP12 | main/Operations_Counter | Heatpump starts (counter)
TOP13 | main/Main_Schedule_State | Main thermostat schedule state (inactive - active)
TOP14 | main/Outside_Temp | Outside ambient temperature (°C)
TOP15 | main/Heat_Energy_Production | Thermal heat power production (Watt)
TOP16 | main/Heat_Energy_Consumption | Elektrical heat power consumption at heat mode (Watt)
TOP15 | main/Heat_Power_Production | Thermal heat power production (Watt)
TOP16 | main/Heat_Power_Consumption | Elektrical heat power consumption at heat mode (Watt)
TOP17 | main/Powerful_Mode_Time | Powerful state in minutes (0, 1, 2 or 3 x 30min)
TOP18 | main/Quiet_Mode_Level | Quiet mode level (0, 1, 2, 3)
TOP19 | main/Holiday_Mode_State | Holiday mode (0=off, 1=scheduled, 2=active)
Expand All @@ -54,10 +54,10 @@ TOP34 | main/Z2_Heat_Request_Temp | Zone 2 Heat Requested shift temp (-5 to 5) o
TOP35 | main/Z2_Cool_Request_Temp | Zone 2 Cool Requested shift temp (-5 to 5) or direct cool temp (5 to 20)
TOP36 | main/Z1_Water_Temp | Zone 1 Water outlet temperature (°C)
TOP37 | main/Z2_Water_Temp | Zone 2 Water outlet temperature (°C)
TOP38 | main/Cool_Energy_Production | Thermal cooling power production (Watt)
TOP39 | main/Cool_Energy_Consumption | Elektrical cooling power consumption (Watt)
TOP40 | main/DHW_Energy_Production | Thermal DHW power production (Watt)
TOP41 | main/DHW_Energy_Consumption | Elektrical DHW power consumption (Watt)
TOP38 | main/Cool_Power_Production | Thermal cooling power production (Watt)
TOP39 | main/Cool_Power_Consumption | Elektrical cooling power consumption (Watt)
TOP40 | main/DHW_Power_Production | Thermal DHW power production (Watt)
TOP41 | main/DHW_Power_Consumption | Elektrical DHW power consumption (Watt)
TOP42 | main/Z1_Water_Target_Temp | Zone 1 water target temperature (°C)
TOP43 | main/Z2_Water_Target_Temp | Zone 2 water target temperature (°C)
TOP44 | main/Error | Last active Error from Heat Pump
Expand Down Expand Up @@ -191,7 +191,9 @@ SET27 | SetBufferDelta | Set buffer tank delta | 0 - 10
SET28 | SetBuffer | Set buffer installed | 0=not installed, 1=installed
SET29 | SetHeatingOffOutdoorTemp | Set Outdoor Temperature to stop heating | 5 to 35

*If you operate your heatpump with direct temperature setup: topics ending xxxRequestTemperature will set the absolute target temperature*
*If you operate your heatpump in water mode with direct temperature setup: topics ending xxxRequestTemperature will set the absolute target temperature.*

*But if you operature your heatpump in internal/external thermostat or thermistor mode with direct temperature, you can not use these SET15 and other topics to set the direct temperature. The direct temperature in that modes is stored in the high target compenstation curve value. So to change the requested direct temperature in those modes, use the SET16 to set this value. Maybe this weird behaviour is different for newer heatpump types. So if your heatpump works different, please feel free to updates this note in github.*

*To send Heating/Cooling Curves on topic SET16 you need to send a flattened JSON document. For example:*

Expand Down
Loading

0 comments on commit f15a0fe

Please sign in to comment.