Browse Source

Merge remote-tracking branch 'refs/remotes/origin/development03' into development03

pull/861/head
Frank 2 years ago
parent
commit
7857424fe7
  1. 10
      .github/ISSUE_TEMPLATE/report.yaml
  2. 4
      src/CHANGES.md
  3. 2
      src/app.cpp
  4. 6
      src/app.h
  5. 2
      src/defines.h
  6. 24
      src/hm/hmPayload.h
  7. 88
      src/hm/hmRadio.h
  8. 125
      src/hm/miPayload.h
  9. 2
      src/web/html/style.css

10
.github/ISSUE_TEMPLATE/report.yaml

@ -29,14 +29,6 @@ body:
- RaspberryPi - RaspberryPi
validations: validations:
required: true required: true
- type: input
id: model
attributes:
label: Model name
description: Please give us a precise description of your hardware and/or a link to the vendor
placeholder:
validations:
required: false
- type: dropdown - type: dropdown
id: assembly-type id: assembly-type
attributes: attributes:
@ -111,7 +103,7 @@ body:
attributes: attributes:
label: Github Hash label: Github Hash
description: Which GitHub hash has the build of our software ? description: Which GitHub hash has the build of our software ?
placeholder: 0000000 placeholder: abc1234
validations: validations:
required: true required: true
- type: dropdown - type: dropdown

4
src/CHANGES.md

@ -1,5 +1,9 @@
# Development Changes # Development Changes
## 0.6.4 - 2023-04-06
* merge PR #846, improved NRF24 communication and MI, thx @beegee3 & @rejoe2
* merge PR #859, fix burger menu height, thx @ThomasPohl
## 0.6.3 - 2023-04-04 ## 0.6.3 - 2023-04-04
* fix login, password length was not checked #852 * fix login, password length was not checked #852
* merge PR #854 optimize browser caching, thx @tastendruecker123 #828 * merge PR #854 optimize browser caching, thx @tastendruecker123 #828

2
src/app.cpp

@ -51,6 +51,7 @@ void app::setup() {
mMiPayload.setup(this, &mSys, &mStat, mConfig->nrf.maxRetransPerPyld, &mTimestamp); mMiPayload.setup(this, &mSys, &mStat, mConfig->nrf.maxRetransPerPyld, &mTimestamp);
mMiPayload.enableSerialDebug(mConfig->serial.debug); mMiPayload.enableSerialDebug(mConfig->serial.debug);
mMiPayload.addPayloadListener(std::bind(&app::payloadEventListener, this, std::placeholders::_1));
// DBGPRINTLN("--- after payload"); // DBGPRINTLN("--- after payload");
// DBGPRINTLN(String(ESP.getFreeHeap())); // DBGPRINTLN(String(ESP.getFreeHeap()));
@ -67,6 +68,7 @@ void app::setup() {
mMqtt.setup(&mConfig->mqtt, mConfig->sys.deviceName, mVersion, &mSys, &mTimestamp); mMqtt.setup(&mConfig->mqtt, mConfig->sys.deviceName, mVersion, &mSys, &mTimestamp);
mMqtt.setSubscriptionCb(std::bind(&app::mqttSubRxCb, this, std::placeholders::_1)); mMqtt.setSubscriptionCb(std::bind(&app::mqttSubRxCb, this, std::placeholders::_1));
mPayload.addAlarmListener(std::bind(&PubMqttType::alarmEventListener, &mMqtt, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); mPayload.addAlarmListener(std::bind(&PubMqttType::alarmEventListener, &mMqtt, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
mMiPayload.addAlarmListener(std::bind(&PubMqttType::alarmEventListener, &mMqtt, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));
} }
#endif #endif
setupLed(); setupLed();

6
src/app.h

@ -141,8 +141,12 @@ class app : public IApp, public ah::Scheduler {
} }
void ivSendHighPrio(Inverter<> *iv) { void ivSendHighPrio(Inverter<> *iv) {
if(mIVCommunicationOn) // only send commands if communcation is enabled if(mIVCommunicationOn) { // only send commands if communcation is enabled
if (iv->ivGen == IV_HM)
mPayload.ivSendHighPrio(iv); mPayload.ivSendHighPrio(iv);
else if (iv->ivGen == IV_MI)
mMiPayload.ivSendHighPrio(iv);
}
} }
bool getMqttIsConnected() { bool getMqttIsConnected() {

2
src/defines.h

@ -13,7 +13,7 @@
//------------------------------------- //-------------------------------------
#define VERSION_MAJOR 0 #define VERSION_MAJOR 0
#define VERSION_MINOR 6 #define VERSION_MINOR 6
#define VERSION_PATCH 3 #define VERSION_PATCH 4
//------------------------------------- //-------------------------------------
typedef struct { typedef struct {

24
src/hm/hmPayload.h

@ -64,7 +64,7 @@ class HmPayload {
} }
void loop() { void loop() {
if(NULL != mHighPrioIv) { if (NULL != mHighPrioIv) {
ivSend(mHighPrioIv, true); ivSend(mHighPrioIv, true);
mHighPrioIv = NULL; mHighPrioIv = NULL;
} }
@ -110,20 +110,22 @@ class HmPayload {
process(false); // no retransmit process(false); // no retransmit
if (!mPayload[iv->id].complete) { if (!mPayload[iv->id].complete) {
if (MAX_PAYLOAD_ENTRIES == mPayload[iv->id].maxPackId) if (mSerialDebug)
DPRINT_IVID(DBG_INFO, iv->id);
if (MAX_PAYLOAD_ENTRIES == mPayload[iv->id].maxPackId) {
mStat->rxFailNoAnser++; // got nothing mStat->rxFailNoAnser++; // got nothing
else if (mSerialDebug)
DBGPRINTLN(F("enqueued cmd failed/timeout"));
} else {
mStat->rxFail++; // got fragments but not complete response mStat->rxFail++; // got fragments but not complete response
iv->setQueuedCmdFinished(); // command failed
if (mSerialDebug) { if (mSerialDebug) {
DPRINTLN(DBG_INFO, F("enqueued cmd failed/timeout")); DBGPRINT(F("no complete Payload received! (retransmits: "));
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINT(F("no Payload received! (retransmits: "));
DBGPRINT(String(mPayload[iv->id].retransmits)); DBGPRINT(String(mPayload[iv->id].retransmits));
DBGPRINTLN(F(")")); DBGPRINTLN(F(")"));
} }
} }
iv->setQueuedCmdFinished(); // command failed
}
} }
} }
@ -207,6 +209,8 @@ class HmPayload {
iv->clearCmdQueue(); iv->clearCmdQueue();
iv->enqueCommand<InfoCommand>(SystemConfigPara); // read back power limit iv->enqueCommand<InfoCommand>(SystemConfigPara); // read back power limit
if(mHighPrioIv == NULL) // do it immediately if possible
mHighPrioIv = iv;
} }
iv->devControlCmd = Init; iv->devControlCmd = Init;
} }
@ -390,8 +394,8 @@ class HmPayload {
} }
void reset(uint8_t id) { void reset(uint8_t id) {
DPRINT(DBG_INFO, "resetPayload: id: "); DPRINT_IVID(DBG_INFO, id);
DBGPRINTLN(String(id)); DBGPRINTLN(F("resetPayload"));
memset(mPayload[id].len, 0, MAX_PAYLOAD_ENTRIES); memset(mPayload[id].len, 0, MAX_PAYLOAD_ENTRIES);
mPayload[id].txCmd = 0; mPayload[id].txCmd = 0;
mPayload[id].gotFragment = false; mPayload[id].gotFragment = false;

88
src/hm/hmRadio.h

@ -52,12 +52,15 @@ template <uint8_t IRQ_PIN = DEF_IRQ_PIN, uint8_t CE_PIN = DEF_CE_PIN, uint8_t CS
class HmRadio { class HmRadio {
public: public:
HmRadio() : mNrf24(CE_PIN, CS_PIN, SPI_SPEED) { HmRadio() : mNrf24(CE_PIN, CS_PIN, SPI_SPEED) {
if(mSerialDebug) {
DPRINT(DBG_VERBOSE, F("hmRadio.h : HmRadio():mNrf24(CE_PIN: ")); DPRINT(DBG_VERBOSE, F("hmRadio.h : HmRadio():mNrf24(CE_PIN: "));
DPRINT(DBG_VERBOSE, String(CE_PIN)); DBGPRINT(String(CE_PIN));
DPRINT(DBG_VERBOSE, F(", CS_PIN: ")); DBGPRINT(F(", CS_PIN: "));
DPRINT(DBG_VERBOSE, String(CS_PIN)); DBGPRINT(String(CS_PIN));
DPRINT(DBG_VERBOSE, F(", SPI_SPEED: ")); DBGPRINT(F(", SPI_SPEED: "));
DPRINTLN(DBG_VERBOSE, String(SPI_SPEED) + ")"); DBGPRINT(String(SPI_SPEED));
DBGPRINTLN(F(")"));
}
// Depending on the program, the module can work on 2403, 2423, 2440, 2461 or 2475MHz. // Depending on the program, the module can work on 2403, 2423, 2440, 2461 or 2475MHz.
// Channel List 2403, 2423, 2440, 2461, 2475MHz // Channel List 2403, 2423, 2440, 2461, 2475MHz
@ -123,7 +126,7 @@ class HmRadio {
mNrf24.enableDynamicPayloads(); mNrf24.enableDynamicPayloads();
mNrf24.setCRCLength(RF24_CRC_16); mNrf24.setCRCLength(RF24_CRC_16);
mNrf24.setAddressWidth(5); mNrf24.setAddressWidth(5);
mNrf24.openReadingPipe(1, DTU_RADIO_ID); mNrf24.openReadingPipe(1, reinterpret_cast<uint8_t*>(&DTU_RADIO_ID));
// enable all receiving interrupts // enable all receiving interrupts
mNrf24.maskIRQ(false, false, false); mNrf24.maskIRQ(false, false, false);
@ -147,32 +150,31 @@ class HmRadio {
bool tx_ok, tx_fail, rx_ready; bool tx_ok, tx_fail, rx_ready;
mNrf24.whatHappened(tx_ok, tx_fail, rx_ready); // resets the IRQ pin to HIGH mNrf24.whatHappened(tx_ok, tx_fail, rx_ready); // resets the IRQ pin to HIGH
mNrf24.flush_tx(); // empty TX FIFO mNrf24.flush_tx(); // empty TX FIFO
//DBGPRINTLN("TX whatHappened Ch" + String(mRfChLst[mTxChIdx]) + " " + String(tx_ok) + String(tx_fail) + String(rx_ready));
// start listening on the default RX channel // start listening
mRxChIdx = 0;
mNrf24.setChannel(mRfChLst[mRxChIdx]); mNrf24.setChannel(mRfChLst[mRxChIdx]);
mNrf24.startListening(); mNrf24.startListening();
//uint32_t debug_ms = millis(); uint32_t startMicros = micros();
uint16_t cnt = 300; // that is 60 times 5 channels uint32_t loopMillis = millis();
while (0 < cnt--) { while (millis()-loopMillis < 400) {
uint32_t startMillis = millis(); while (micros()-startMicros < 5110) { // listen (4088us or?) 5110us to each channel
while (millis()-startMillis < 4) { // listen 4ms to each channel
if (mIrqRcvd) { if (mIrqRcvd) {
mIrqRcvd = false; mIrqRcvd = false;
if (getReceived()) { // everything received if (getReceived()) { // everything received
//DBGPRINTLN("RX finished Cnt: " + String(300-cnt) + " time used: " + String(millis()-debug_ms)+ " ms");
return true; return true;
} }
} }
yield(); yield();
} }
switchRxCh(); // switch to next RX channel // switch to next RX channel
startMicros = micros();
if(++mRxChIdx >= RF_CHANNELS)
mRxChIdx = 0;
mNrf24.setChannel(mRfChLst[mRxChIdx]);
yield(); yield();
} }
// not finished but time is over // not finished but time is over
//DBGPRINTLN("RX not finished: 300 time used: " + String(millis()-debug_ms)+ " ms");
return true; return true;
} }
@ -205,6 +207,7 @@ class HmRadio {
} else { //MI 2nd gen. specific } else { //MI 2nd gen. specific
switch (cmd) { switch (cmd) {
case TurnOn: case TurnOn:
//mTxBuf[0] = 0x50;
mTxBuf[9] = 0x55; mTxBuf[9] = 0x55;
mTxBuf[10] = 0xaa; mTxBuf[10] = 0xaa;
break; break;
@ -223,11 +226,14 @@ class HmRadio {
} }
cnt++; cnt++;
} }
sendPacket(invId, cnt, isRetransmit, true); sendPacket(invId, cnt, isRetransmit, isNoMI);
} }
void prepareDevInformCmd(uint64_t invId, uint8_t cmd, uint32_t ts, uint16_t alarmMesId, bool isRetransmit, uint8_t reqfld=TX_REQ_INFO) { // might not be necessary to add additional arg. void prepareDevInformCmd(uint64_t invId, uint8_t cmd, uint32_t ts, uint16_t alarmMesId, bool isRetransmit, uint8_t reqfld=TX_REQ_INFO) { // might not be necessary to add additional arg.
DPRINTLN(DBG_DEBUG, F("prepareDevInformCmd 0x") + String(cmd, HEX)); if(mSerialDebug) {
DPRINT(DBG_DEBUG, F("prepareDevInformCmd 0x"));
DPRINTLN(DBG_DEBUG,String(cmd, HEX));
}
initPacket(invId, reqfld, ALL_FRAMES); initPacket(invId, reqfld, ALL_FRAMES);
mTxBuf[10] = cmd; // cid mTxBuf[10] = cmd; // cid
mTxBuf[11] = 0x00; mTxBuf[11] = 0x00;
@ -239,9 +245,9 @@ class HmRadio {
sendPacket(invId, 24, isRetransmit, true); sendPacket(invId, 24, isRetransmit, true);
} }
void sendCmdPacket(uint64_t invId, uint8_t mid, uint8_t pid, bool isRetransmit) { void sendCmdPacket(uint64_t invId, uint8_t mid, uint8_t pid, bool isRetransmit, bool appendCrc16=true) {
initPacket(invId, mid, pid); initPacket(invId, mid, pid);
sendPacket(invId, 10, isRetransmit, false); sendPacket(invId, 10, isRetransmit, appendCrc16);
} }
void dumpBuf(uint8_t buf[], uint8_t len) { void dumpBuf(uint8_t buf[], uint8_t len) {
@ -274,7 +280,6 @@ class HmRadio {
bool getReceived(void) { bool getReceived(void) {
bool tx_ok, tx_fail, rx_ready; bool tx_ok, tx_fail, rx_ready;
mNrf24.whatHappened(tx_ok, tx_fail, rx_ready); // resets the IRQ pin to HIGH mNrf24.whatHappened(tx_ok, tx_fail, rx_ready); // resets the IRQ pin to HIGH
//DBGPRINTLN("RX whatHappened Ch" + String(mRfChLst[mRxChIdx]) + " " + String(tx_ok) + String(tx_fail) + String(rx_ready));
bool isLastPackage = false; bool isLastPackage = false;
while(mNrf24.available()) { while(mNrf24.available()) {
@ -285,31 +290,28 @@ class HmRadio {
p.ch = mRfChLst[mRxChIdx]; p.ch = mRfChLst[mRxChIdx];
p.len = len; p.len = len;
mNrf24.read(p.packet, len); mNrf24.read(p.packet, len);
if (p.packet[0] != 0x00) {
mBufCtrl.push(p); mBufCtrl.push(p);
if (p.packet[0] == (TX_REQ_INFO + ALL_FRAMES)) // response from get information command if (p.packet[0] == (TX_REQ_INFO + ALL_FRAMES)) // response from get information command
isLastPackage = (p.packet[9] > 0x81); // > 0x81 indicates last packet received isLastPackage = (p.packet[9] > ALL_FRAMES); // > ALL_FRAMES indicates last packet received
else if (p.packet[0] == ( 0x0f + ALL_FRAMES) ) // response from MI get information command else if (p.packet[0] == ( 0x0f + ALL_FRAMES) ) // response from MI get information command
isLastPackage = (p.packet[9] > 0x11); // > 0x11 indicates last packet received isLastPackage = (p.packet[9] > 0x10); // > 0x10 indicates last packet received
else if (p.packet[0] != 0x00 && p.packet[0] != 0x88 && p.packet[0] != 0x92) else if ((p.packet[0] != 0x88) && (p.packet[0] != 0x92)) // ignore fragment number zero and MI status messages //#0 was p.packet[0] != 0x00 &&
// ignore fragment number zero and MI status messages
isLastPackage = true; // response from dev control command isLastPackage = true; // response from dev control command
yield();
} }
} }
return isLastPackage; yield();
} }
return isLastPackage;
void switchRxCh() {
mNrf24.stopListening();
// get next channel index
if(++mRxChIdx >= RF_CHANNELS)
mRxChIdx = 0;
mNrf24.setChannel(mRfChLst[mRxChIdx]);
mNrf24.startListening();
} }
void initPacket(uint64_t invId, uint8_t mid, uint8_t pid) { void initPacket(uint64_t invId, uint8_t mid, uint8_t pid) {
DPRINTLN(DBG_VERBOSE, F("initPacket, mid: ") + String(mid, HEX) + F(" pid: ") + String(pid, HEX)); if(mSerialDebug) {
DPRINT(DBG_VERBOSE, F("initPacket, mid: "));
DHEX(mid);
DBGPRINT(F(" pid: "));
DBGHEXLN(pid);
}
memset(mTxBuf, 0, MAX_RF_PAYLOAD_SIZE); memset(mTxBuf, 0, MAX_RF_PAYLOAD_SIZE);
mTxBuf[0] = mid; // message id mTxBuf[0] = mid; // message id
CP_U32_BigEndian(&mTxBuf[1], (invId >> 8)); CP_U32_BigEndian(&mTxBuf[1], (invId >> 8));
@ -317,12 +319,12 @@ class HmRadio {
mTxBuf[9] = pid; mTxBuf[9] = pid;
} }
void sendPacket(uint64_t invId, uint8_t len, bool isRetransmit, bool clear=false) { void sendPacket(uint64_t invId, uint8_t len, bool isRetransmit, bool appendCrc16=true) {
//DPRINTLN(DBG_VERBOSE, F("hmRadio.h:sendPacket")); //DPRINTLN(DBG_VERBOSE, F("hmRadio.h:sendPacket"));
//DPRINTLN(DBG_VERBOSE, "sent packet: #" + String(mSendCnt)); //DPRINTLN(DBG_VERBOSE, "sent packet: #" + String(mSendCnt));
// append crc's // append crc's
if (len > 10) { if (appendCrc16 && (len > 10)) {
// crc control data // crc control data
uint16_t crc = ah::crc16(&mTxBuf[10], len - 10); uint16_t crc = ah::crc16(&mTxBuf[10], len - 10);
mTxBuf[len++] = (crc >> 8) & 0xff; mTxBuf[len++] = (crc >> 8) & 0xff;
@ -332,6 +334,10 @@ class HmRadio {
mTxBuf[len] = ah::crc8(mTxBuf, len); mTxBuf[len] = ah::crc8(mTxBuf, len);
len++; len++;
// set TX and RX channels
mTxChIdx = (mTxChIdx + 1) % RF_CHANNELS;
mRxChIdx = (mTxChIdx + 2) % RF_CHANNELS;
if(mSerialDebug) { if(mSerialDebug) {
DPRINT(DBG_INFO, F("TX ")); DPRINT(DBG_INFO, F("TX "));
DBGPRINT(String(len)); DBGPRINT(String(len));
@ -346,10 +352,6 @@ class HmRadio {
mNrf24.openWritingPipe(reinterpret_cast<uint8_t*>(&invId)); mNrf24.openWritingPipe(reinterpret_cast<uint8_t*>(&invId));
mNrf24.startWrite(mTxBuf, len, false); // false = request ACK response mNrf24.startWrite(mTxBuf, len, false); // false = request ACK response
// switch TX channel for next packet
if(++mTxChIdx >= RF_CHANNELS)
mTxChIdx = 0;
if(isRetransmit) if(isRetransmit)
mRetransmits++; mRetransmits++;
else else

125
src/hm/miPayload.h

@ -25,7 +25,6 @@ typedef struct {
uint8_t txId; uint8_t txId;
uint8_t invId; uint8_t invId;
uint8_t retransmits; uint8_t retransmits;
//uint8_t skipfirstrepeat;
bool gotFragment; bool gotFragment;
/* /*
uint8_t data[MAX_PAYLOAD_ENTRIES][MAX_RF_PAYLOAD_SIZE]; uint8_t data[MAX_PAYLOAD_ENTRIES][MAX_RF_PAYLOAD_SIZE];
@ -70,8 +69,8 @@ class MiPayload {
} }
void loop() { void loop() {
if(NULL != mHighPrioIv) { // && mHighPrioIv->ivGen == IV_MI) { if (NULL != mHighPrioIv) {
ivSend(mHighPrioIv, true); // for devcontrol commands? ivSend(mHighPrioIv, true); // for e.g. devcontrol commands
mHighPrioIv = NULL; mHighPrioIv = NULL;
} }
} }
@ -87,22 +86,23 @@ class MiPayload {
process(false); // no retransmit process(false); // no retransmit
if (!mPayload[iv->id].complete) { if (!mPayload[iv->id].complete) {
if (!mPayload[iv->id].gotFragment)
mStat->rxFailNoAnser++; // got nothing
else
mStat->rxFail++; // got fragments but not complete response
iv->setQueuedCmdFinished(); // command failed
if (mSerialDebug) if (mSerialDebug)
DPRINT_IVID(DBG_INFO, iv->id); DPRINT_IVID(DBG_INFO, iv->id);
if (!mPayload[iv->id].gotFragment) {
mStat->rxFailNoAnser++; // got nothing
if (mSerialDebug)
DBGPRINTLN(F("enqueued cmd failed/timeout")); DBGPRINTLN(F("enqueued cmd failed/timeout"));
} else {
mStat->rxFail++; // got "fragments" (part of the required messages)
// but no complete set of responses
if (mSerialDebug) { if (mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id); DBGPRINT(F("no complete Payload received! (retransmits: "));
DBGPRINT(F("no Payload received! (retransmits: "));
DBGPRINT(String(mPayload[iv->id].retransmits)); DBGPRINT(String(mPayload[iv->id].retransmits));
DBGPRINTLN(F(")")); DBGPRINTLN(F(")"));
} }
} }
iv->setQueuedCmdFinished(); // command failed
}
} }
} }
@ -148,9 +148,10 @@ class MiPayload {
if (cmd == 0x01 || cmd == SystemConfigPara ) { //0x1 and 0x05 for HM-types if (cmd == 0x01 || cmd == SystemConfigPara ) { //0x1 and 0x05 for HM-types
cmd = 0x0f; // for MI, these seem to make part of the Polling the device software and hardware version number command cmd = 0x0f; // for MI, these seem to make part of the Polling the device software and hardware version number command
cmd2 = cmd == SystemConfigPara ? 0x01 : 0x00; //perhaps we can only try to get second frame? cmd2 = cmd == SystemConfigPara ? 0x01 : 0x00; //perhaps we can only try to get second frame?
mSys->Radio.sendCmdPacket(iv->radioId.u64, cmd, cmd2, false); mSys->Radio.sendCmdPacket(iv->radioId.u64, cmd, cmd2, false, false);
} else { } else {
mSys->Radio.prepareDevInformCmd(iv->radioId.u64, cmd2, mPayload[iv->id].ts, iv->alarmMesIndex, false, cmd); //mSys->Radio.prepareDevInformCmd(iv->radioId.u64, cmd2, mPayload[iv->id].ts, iv->alarmMesIndex, false, cmd);
mSys->Radio.sendCmdPacket(iv->radioId.u64, cmd, cmd2, false, false);
}; };
mPayload[iv->id].txCmd = cmd; mPayload[iv->id].txCmd = cmd;
@ -232,42 +233,39 @@ const byteAssign_t InfoAssignment[] = {
iv->setValue(i, rec, (float) ((p->packet[(12+2*i)] << 8) + p->packet[(13+2*i)])/1); iv->setValue(i, rec, (float) ((p->packet[(12+2*i)] << 8) + p->packet[(13+2*i)])/1);
} }
iv->isConnected = true; iv->isConnected = true;
mPayload[iv->id].gotFragment = true;
if(mSerialDebug) { if(mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id); DPRINT_IVID(DBG_INFO, iv->id);
DPRINT(DBG_INFO,F("HW_VER is ")); DPRINT(DBG_INFO,F("HW_VER is "));
DBGPRINTLN(String((p->packet[24] << 8) + p->packet[25])); DBGPRINTLN(String((p->packet[24] << 8) + p->packet[25]));
} }
/*iv->setQueuedCmdFinished();
mSys->Radio.sendCmdPacket(iv->radioId.u64, 0x0f, 0x01, false);*/
} else if ( p->packet[9] == 0x01 || p->packet[9] == 0x10 ) {//second frame for MI, 3rd gen. answers in 0x10 } else if ( p->packet[9] == 0x01 || p->packet[9] == 0x10 ) {//second frame for MI, 3rd gen. answers in 0x10
DPRINT_IVID(DBG_INFO, iv->id); DPRINT_IVID(DBG_INFO, iv->id);
if ( p->packet[9] == 0x01 ) { if ( p->packet[9] == 0x01 ) {
DBGPRINTLN(F("got 2nd frame (hw info)")); DBGPRINTLN(F("got 2nd frame (hw info)"));
} else {
DBGPRINTLN(F("3rd gen. inverter!")); // see table in OpenDTU code, DevInfoParser.cpp devInfo[]
}
// xlsx: HW_ECapValue is total energy?!? (data coll. inst. #154)
DPRINT(DBG_INFO,F("HW_PartNo ")); DPRINT(DBG_INFO,F("HW_PartNo "));
DBGPRINTLN(String((uint32_t) (((p->packet[10] << 8) | p->packet[11]) << 8 | p->packet[12]) << 8 | p->packet[13])); DBGPRINTLN(String((uint32_t) (((p->packet[10] << 8) | p->packet[11]) << 8 | p->packet[12]) << 8 | p->packet[13]));
//DBGPRINTLN(String((p->packet[12] << 8) + p->packet[13])); mPayload[iv->id].gotFragment = true;
if ( p->packet[9] == 0x01 ) {
iv->setValue(iv->getPosByChFld(0, FLD_YT, rec), rec, (float) ((p->packet[20] << 8) + p->packet[21])/1); iv->setValue(iv->getPosByChFld(0, FLD_YT, rec), rec, (float) ((p->packet[20] << 8) + p->packet[21])/1);
if(mSerialDebug) { if(mSerialDebug) {
DPRINT(DBG_INFO,F("HW_ECapValue "));
DBGPRINTLN(String((p->packet[20] << 8) + p->packet[21]));
DPRINT(DBG_INFO,F("HW_FB_TLmValue ")); DPRINT(DBG_INFO,F("HW_FB_TLmValue "));
DBGPRINTLN(String((p->packet[14] << 8) + p->packet[15])); DBGPRINTLN(String((p->packet[14] << 8) + p->packet[15]));
DPRINT(DBG_INFO,F("HW_FB_ReSPRT ")); DPRINT(DBG_INFO,F("HW_FB_ReSPRT "));
DBGPRINTLN(String((p->packet[16] << 8) + p->packet[17])); DBGPRINTLN(String((p->packet[16] << 8) + p->packet[17]));
DPRINT(DBG_INFO,F("HW_GridSamp_ResValule ")); DPRINT(DBG_INFO,F("HW_GridSamp_ResValule "));
DBGPRINTLN(String((p->packet[18] << 8) + p->packet[19])); DBGPRINTLN(String((p->packet[18] << 8) + p->packet[19]));
DPRINT(DBG_INFO,F("HW_ECapValue "));
DBGPRINTLN(String((p->packet[20] << 8) + p->packet[21]));
} }
} else {
DBGPRINTLN(F("3rd gen. inverter!")); // see table in OpenDTU code, DevInfoParser.cpp devInfo[]
} }
} else if ( p->packet[9] == 0x12 ) {//3rd frame } else if ( p->packet[9] == 0x12 ) {//3rd frame
DPRINT_IVID(DBG_INFO, iv->id); DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINTLN(F("got 3rd frame (hw info)")); DBGPRINTLN(F("got 3rd frame (hw info)"));
iv->setQueuedCmdFinished(); iv->setQueuedCmdFinished();
mPayload[iv->id].complete = true;
mStat->rxSuccess++; mStat->rxSuccess++;
} }
@ -347,7 +345,9 @@ const byteAssign_t InfoAssignment[] = {
payloadLen -= 2; payloadLen -= 2;
if (mSerialDebug) { if (mSerialDebug) {
DPRINT(DBG_INFO, F("Payload (") + String(payloadLen) + "): "); DPRINT(DBG_INFO, F("Payload ("));
DBGPRINT(String(payloadLen));
DBGPRINT("): ");
mSys->Radio.dumpBuf(payload, payloadLen); mSys->Radio.dumpBuf(payload, payloadLen);
} }
@ -442,14 +442,14 @@ const byteAssign_t InfoAssignment[] = {
mPayload[iv->id].retransmits = mMaxRetrans; mPayload[iv->id].retransmits = mMaxRetrans;
} else if ( cmd == 0x0f ) { } else if ( cmd == 0x0f ) {
//hard/firmware request //hard/firmware request
mSys->Radio.sendCmdPacket(iv->radioId.u64, 0x0f, 0x00, true); mSys->Radio.sendCmdPacket(iv->radioId.u64, 0x0f, 0x00, true, false);
//iv->setQueuedCmdFinished(); //iv->setQueuedCmdFinished();
//cmd = iv->getQueuedCmd(); //cmd = iv->getQueuedCmd();
} else { } else {
bool change = false; bool change = false;
if ( cmd >= 0x36 && cmd < 0x39 ) { // MI-1500 Data command if ( cmd >= 0x36 && cmd < 0x39 ) { // MI-1500 Data command
//cmd++; // just request the next channel if (cmd > 0x36 && mPayload[iv->id].retransmits==1) // first request for the upper channels
//change = true; change = true;
} else if ( cmd == 0x09 ) {//MI single or dual channel device } else if ( cmd == 0x09 ) {//MI single or dual channel device
if ( mPayload[iv->id].dataAB[CH1] && iv->type == INV_TYPE_2CH ) { if ( mPayload[iv->id].dataAB[CH1] && iv->type == INV_TYPE_2CH ) {
if (!mPayload[iv->id].stsAB[CH1] && mPayload[iv->id].retransmits<2) {} if (!mPayload[iv->id].stsAB[CH1] && mPayload[iv->id].retransmits<2) {}
@ -479,8 +479,8 @@ const byteAssign_t InfoAssignment[] = {
} }
DBGPRINT(F(" 0x")); DBGPRINT(F(" 0x"));
DBGHEXLN(cmd); DBGHEXLN(cmd);
//mSys->Radio.sendCmdPacket(iv->radioId.u64, cmd, cmd, true); mSys->Radio.sendCmdPacket(iv->radioId.u64, cmd, cmd, true, false);
mSys->Radio.prepareDevInformCmd(iv->radioId.u64, cmd, mPayload[iv->id].ts, iv->alarmMesIndex, true, cmd); //mSys->Radio.prepareDevInformCmd(iv->radioId.u64, cmd, mPayload[iv->id].ts, iv->alarmMesIndex, true, cmd);
yield(); yield();
} }
} }
@ -496,7 +496,8 @@ const byteAssign_t InfoAssignment[] = {
DBGPRINT(F("prepareDevInformCmd 0x")); DBGPRINT(F("prepareDevInformCmd 0x"));
DBGHEXLN(mPayload[iv->id].txCmd); DBGHEXLN(mPayload[iv->id].txCmd);
mSys->Radio.prepareDevInformCmd(iv->radioId.u64, mPayload[iv->id].txCmd, mPayload[iv->id].ts, iv->alarmMesIndex, true); //mSys->Radio.prepareDevInformCmd(iv->radioId.u64, mPayload[iv->id].txCmd, mPayload[iv->id].ts, iv->alarmMesIndex, true);
mSys->Radio.sendCmdPacket(iv->radioId.u64, mPayload[iv->id].txCmd, mPayload[iv->id].txCmd, false, false);
} }
} }
/*else { // payload complete /*else { // payload complete
@ -641,7 +642,6 @@ const byteAssign_t InfoAssignment[] = {
( p->packet[0] == 0x91 || p->packet[0] == (0x37 + ALL_FRAMES) ) ? CH2 : ( p->packet[0] == 0x91 || p->packet[0] == (0x37 + ALL_FRAMES) ) ? CH2 :
p->packet[0] == (0x38 + ALL_FRAMES) ? CH3 : p->packet[0] == (0x38 + ALL_FRAMES) ? CH3 :
CH4; CH4;
//DPRINTLN(DBG_INFO, F("(#") + String(iv->id) + F(") data msg 0x") + String(p->packet[0], HEX) + F(" channel ") + datachan);
// count in RF_communication_protocol.xlsx is with offset = -1 // count in RF_communication_protocol.xlsx is with offset = -1
iv->setValue(iv->getPosByChFld(datachan, FLD_UDC, rec), rec, (float)((p->packet[9] << 8) + p->packet[10])/10); iv->setValue(iv->getPosByChFld(datachan, FLD_UDC, rec), rec, (float)((p->packet[9] << 8) + p->packet[10])/10);
yield(); yield();
@ -656,12 +656,11 @@ const byteAssign_t InfoAssignment[] = {
yield(); yield();
iv->setValue(iv->getPosByChFld(0, FLD_T, rec), rec, (float) ((int16_t)(p->packet[21] << 8) + p->packet[22])/10); iv->setValue(iv->getPosByChFld(0, FLD_T, rec), rec, (float) ((int16_t)(p->packet[21] << 8) + p->packet[22])/10);
iv->setValue(iv->getPosByChFld(0, FLD_IRR, rec), rec, (float) (calcIrradiation(iv, datachan))); iv->setValue(iv->getPosByChFld(0, FLD_IRR, rec), rec, (float) (calcIrradiation(iv, datachan)));
//AC Power is missing; we may have to calculate, as no respective data is in payload
if ( datachan < 3 ) { if ( datachan < 3 ) {
mPayload[iv->id].dataAB[datachan] = true; mPayload[iv->id].dataAB[datachan] = true;
} }
if ( !mPayload[iv->id].dataAB[CH0] && mPayload[iv->id].dataAB[CH2] && mPayload[iv->id].dataAB[CH2] ) { if ( !mPayload[iv->id].dataAB[CH0] && mPayload[iv->id].dataAB[CH1] && mPayload[iv->id].dataAB[CH2] ) {
mPayload[iv->id].dataAB[CH0] = true; mPayload[iv->id].dataAB[CH0] = true;
} }
@ -687,17 +686,13 @@ const byteAssign_t InfoAssignment[] = {
mSys->Radio.prepareDevInformCmd(iv->radioId.u64, cmd, mPayload[iv->id].ts, iv->alarmMesIndex, false, cmd); mSys->Radio.prepareDevInformCmd(iv->radioId.u64, cmd, mPayload[iv->id].ts, iv->alarmMesIndex, false, cmd);
mPayload[iv->id].txCmd = cmd;*/ mPayload[iv->id].txCmd = cmd;*/
mPayload[iv->id].txCmd++; mPayload[iv->id].txCmd++;
if (mPayload[iv->id].retransmits) mPayload[iv->id].retransmits = 0; // reserve retransmissions for each response
mPayload[iv->id].retransmits--; // reserve retransmissions for each response
mPayload[iv->id].complete = false; mPayload[iv->id].complete = false;
} }
else if (p->packet[0] == (0x39 + ALL_FRAMES) ) { /*else if ( p->packet[0] == (0x39 + ALL_FRAMES) ) {
/*uint8_t cmd = p->packet[0] - ALL_FRAMES + 1;
mSys->Radio.prepareDevInformCmd(iv->radioId.u64, cmd, mPayload[iv->id].ts, iv->alarmMesIndex, false, cmd);
mPayload[iv->id].txCmd = cmd;*/
mPayload[iv->id].complete = true; mPayload[iv->id].complete = true;
} }*/
/*if (iv->alarmMesIndex < rec->record[iv->getPosByChFld(0, FLD_EVT, rec)]){ /*if (iv->alarmMesIndex < rec->record[iv->getPosByChFld(0, FLD_EVT, rec)]){
iv->alarmMesIndex = rec->record[iv->getPosByChFld(0, FLD_EVT, rec)]; iv->alarmMesIndex = rec->record[iv->getPosByChFld(0, FLD_EVT, rec)];
@ -709,16 +704,7 @@ const byteAssign_t InfoAssignment[] = {
} }
if ( mPayload[iv->id].complete || //4ch device /*
(iv->type != INV_TYPE_4CH //other devices
&& mPayload[iv->id].dataAB[CH0]
&& mPayload[iv->id].stsAB[CH0])) {
miComplete(iv);
}
/*
if(AlarmData == mPayload[iv->id].txCmd) { if(AlarmData == mPayload[iv->id].txCmd) {
uint8_t i = 0; uint8_t i = 0;
uint16_t code; uint16_t code;
@ -732,12 +718,20 @@ const byteAssign_t InfoAssignment[] = {
yield(); yield();
} }
}*/ }*/
//if ( mPayload[iv->id].complete || //4ch device
if ( p->packet[0] == (0x39 + ALL_FRAMES) || //4ch device - last message
(iv->type != INV_TYPE_4CH //other devices
&& mPayload[iv->id].dataAB[CH0]
&& mPayload[iv->id].stsAB[CH0])) {
miComplete(iv);
}
} }
void miComplete(Inverter<> *iv) { void miComplete(Inverter<> *iv) {
if (mPayload[iv->id].complete) if ( mPayload[iv->id].complete ) // && iv->type != INV_TYPE_4CH)
return; //if we got second message as well in repreated attempt return; // if we got second message as well in repreated attempt
mPayload[iv->id].complete = true; // For 2 CH devices, this might be too short... mPayload[iv->id].complete = true;
DPRINT_IVID(DBG_INFO, iv->id); DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINTLN(F("got all msgs")); DBGPRINTLN(F("got all msgs"));
record_t<> *rec = iv->getRecordStruct(RealTimeRunData_Debug); record_t<> *rec = iv->getRecordStruct(RealTimeRunData_Debug);
@ -758,7 +752,7 @@ const byteAssign_t InfoAssignment[] = {
iv->setQueuedCmdFinished(); iv->setQueuedCmdFinished();
mStat->rxSuccess++; mStat->rxSuccess++;
yield(); yield();
notify(mPayload[iv->id].txCmd); notify(RealTimeRunData_Debug); //iv->type == INV_TYPE_4CH ? 0x36 : 0x09 );
} }
bool build(uint8_t id, bool *complete) { bool build(uint8_t id, bool *complete) {
@ -778,6 +772,27 @@ const byteAssign_t InfoAssignment[] = {
return true; return true;
} }
/* uint16_t mParseAlarmLog(uint8_t id, uint8_t pyld[], uint8_t len, uint32_t *start, uint32_t *endTime) {
uint8_t startOff = 2 + id * ALARM_LOG_ENTRY_SIZE;
if((startOff + ALARM_LOG_ENTRY_SIZE) > len)
return 0;
uint16_t wCode = ((uint16_t)pyld[startOff]) << 8 | pyld[startOff+1];
uint32_t startTimeOffset = 0, endTimeOffset = 0;
if (((wCode >> 13) & 0x01) == 1) // check if is AM or PM
startTimeOffset = 12 * 60 * 60;
if (((wCode >> 12) & 0x01) == 1) // check if is AM or PM
endTimeOffset = 12 * 60 * 60;
*start = (((uint16_t)pyld[startOff + 4] << 8) | ((uint16_t)pyld[startOff + 5])) + startTimeOffset;
*endTime = (((uint16_t)pyld[startOff + 6] << 8) | ((uint16_t)pyld[startOff + 7])) + endTimeOffset;
DPRINTLN(DBG_INFO, "Alarm #" + String(pyld[startOff+1]) + " '" + String(getAlarmStr(pyld[startOff+1])) + "' start: " + ah::getTimeStr(*start) + ", end: " + ah::getTimeStr(*endTime));
return pyld[startOff+1];
}
*/
void reset(uint8_t id, bool clrSts = false) { void reset(uint8_t id, bool clrSts = false) {
DPRINT_IVID(DBG_INFO, id); DPRINT_IVID(DBG_INFO, id);
DBGPRINTLN(F("resetPayload")); DBGPRINTLN(F("resetPayload"));

2
src/web/html/style.css

@ -92,7 +92,7 @@ svg.icon {
.title { .title {
background-color: var(--primary); background-color: var(--primary);
color: #fff !important; color: #fff !important;
padding-left: 80px !important padding: 15px 14px 16px 80px !important
} }
.topnav .icon span { .topnav .icon span {

Loading…
Cancel
Save