Browse Source

0.8.1

* added tx channel heuristics (per inverter)
* fix statistics counter
pull/1222/head
lumapu 1 year ago
parent
commit
f1dfd328cc
  1. 7
      src/CHANGES.md
  2. 122
      src/app.cpp
  3. 13
      src/app.h
  4. 2
      src/appInterface.h
  5. 4
      src/defines.h
  6. 20
      src/hm/CommQueue.h
  7. 49
      src/hm/Communication.h
  8. 117
      src/hm/Heuristic.h
  9. 98
      src/hm/hmInverter.h
  10. 494
      src/hm/hmPayload.h
  11. 40
      src/hm/hmRadio.h
  12. 844
      src/hm/miPayload.h
  13. 11
      src/web/RestApi.h

7
src/CHANGES.md

@ -1,5 +1,12 @@
# Development Changes
## 0.8.1 - 2023-10-31
* added tx channel heuristics (per inverter)
* fix statistics counter
## 0.8.0 - 2023-10-??
* switched to new communication scheme
## 0.7.66 - 2023-10-04
* prepared PA-Level for CMT
* removed settings for number of retransmits, its fixed to `5` now

122
src/app.cpp

@ -74,15 +74,6 @@ void app::setup() {
});
}
/*mPayload.setup(this, &mSys, &mTimestamp);
mPayload.enableSerialDebug(mConfig->serial.debug);
mPayload.addPayloadListener(std::bind(&app::payloadEventListener, this, std::placeholders::_1, std::placeholders::_2));
if (mConfig->nrf.enabled) {
mMiPayload.setup(this, &mSys, &mTimestamp);
mMiPayload.enableSerialDebug(mConfig->serial.debug);
mMiPayload.addPayloadListener(std::bind(&app::payloadEventListener, this, std::placeholders::_1, std::placeholders::_2));
}*/
if(mConfig->nrf.enabled) {
if (!mNrfRadio.isChipConnected())
DPRINTLN(DBG_WARN, F("WARNING! your NRF24 module can't be reached, check the wiring"));
@ -95,8 +86,6 @@ void app::setup() {
mMqtt.setup(&mConfig->mqtt, mConfig->sys.deviceName, mVersion, &mSys, &mTimestamp, &mUptime);
mMqtt.setSubscriptionCb(std::bind(&app::mqttSubRxCb, this, std::placeholders::_1));
mCommunication.addAlarmListener([this](Inverter<> *iv) { mMqtt.alarmEvent(iv); });
//mPayload.addAlarmListener([this](Inverter<> *iv) { mMqtt.alarmEvent(iv); });
//mMiPayload.addAlarmListener([this](Inverter<> *iv) { mMqtt.alarmEvent(iv); });
}
#endif
setupLed();
@ -124,7 +113,6 @@ void app::setup() {
//-----------------------------------------------------------------------------
void app::loop(void) {
ah::Scheduler::loop();
//bool processPayload = false;
mNrfRadio.loop();
#if defined(ESP32)
@ -132,66 +120,6 @@ void app::loop(void) {
#endif
mCommunication.loop();
/*if (mNrfRadio.loop() && mConfig->nrf.enabled) {
while (!mNrfRadio.mBufCtrl.empty()) {
packet_t *p = &mNrfRadio.mBufCtrl.front();
if (mConfig->serial.debug) {
DPRINT(DBG_INFO, F("RX "));
DBGPRINT(String(p->len));
DBGPRINT(F(" CH"));
DBGPRINT(String(p->ch));
DBGPRINT(F(", "));
DBGPRINT(String(p->rssi));
DBGPRINT(F("dBm | "));
ah::dumpBuf(p->packet, p->len);
}
Inverter<> *iv = mSys.findInverter(&p->packet[1]);
if (NULL != iv) {
iv->radioStatistics.frmCnt++;
if (IV_MI == iv->ivGen)
mMiPayload.add(iv, p);
else
mPayload.add(iv, p);
}
mNrfRadio.mBufCtrl.pop();
processPayload = true;
yield();
}
mMiPayload.process(true);
}
#if defined(ESP32)
if (mCmtRadio.loop() && mConfig->cmt.enabled) {
while (!mCmtRadio.mBufCtrl.empty()) {
packet_t *p = &mCmtRadio.mBufCtrl.front();
if (mConfig->serial.debug) {
DPRINT(DBG_INFO, F("RX "));
DBGPRINT(String(p->len));
DBGPRINT(F(", "));
DBGPRINT(String(p->rssi));
DBGPRINT(F("dBm | "));
ah::dumpBuf(p->packet, p->len);
}
Inverter<> *iv = mSys.findInverter(&p->packet[1]);
if(NULL != iv) {
iv->radioStatistics.frmCnt++;
if((iv->ivGen == IV_HMS) || (iv->ivGen == IV_HMT))
mPayload.add(iv, p);
}
mCmtRadio.mBufCtrl.pop();
processPayload = true;
yield();
}
}
#endif
if(processPayload)
mPayload.process(true);
mPayload.loop();
mMiPayload.loop();*/
if (mMqttEnabled && mNetworkConnected)
mMqtt.loop();
}
@ -293,7 +221,7 @@ void app::tickNtpUpdate(void) {
// immediately start communicating
if (isOK && mSendFirst) {
mSendFirst = false;
//once(std::bind(&app::tickSend, this), 2, "senOn");
once(std::bind(&app::tickSend, this), 1, "senOn");
}
mMqttReconnect = false;
@ -424,54 +352,6 @@ void app::tickSend(void) {
}
}
/*if(mConfig->nrf.enabled) {
if(!mNrfRadio.isChipConnected()) {
DPRINTLN(DBG_WARN, F("NRF24 not connected!"));
}
}
if (mIVCommunicationOn) {
if (!mNrfRadio.mBufCtrl.empty()) {
if (mConfig->serial.debug) {
DPRINT(DBG_DEBUG, F("recbuf not empty! #"));
DBGPRINTLN(String(mNrfRadio.mBufCtrl.size()));
}
}
#if defined(ESP32)
if (!mCmtRadio.mBufCtrl.empty()) {
if (mConfig->serial.debug) {
DPRINT(DBG_INFO, F("recbuf not empty! #"));
DBGPRINTLN(String(mCmtRadio.mBufCtrl.size()));
}
}
#endif
int8_t maxLoop = MAX_NUM_INVERTERS;
Inverter<> *iv = mSys.getInverterByPos(mSendLastIvId);
while(maxLoop > 0) {
do {
mSendLastIvId = ((MAX_NUM_INVERTERS - 1) == mSendLastIvId) ? 0 : mSendLastIvId + 1;
iv = mSys.getInverterByPos(mSendLastIvId);
} while ((NULL == iv) && ((maxLoop--) > 0));
if(NULL != iv)
if(iv->config->enabled)
break;
}
if (NULL != iv) {
if (iv->config->enabled) {
if((iv->ivGen == IV_MI) && mConfig->nrf.enabled)
mMiPayload.ivSend(iv);
else
mPayload.ivSend(iv);
}
}
} else {
if (mConfig->serial.debug)
DPRINTLN(DBG_WARN, F("Time not set or it is night time, therefore no communication to the inverter!"));
}
yield();*/
updateLed();
}

13
src/app.h

@ -15,8 +15,6 @@
#include "hm/hmSystem.h"
#include "hm/hmRadio.h"
#include "hms/hmsRadio.h"
//#include "hm/hmPayload.h"
//#include "hm/miPayload.h"
#include "publisher/pubMqtt.h"
#include "publisher/pubSerial.h"
#include "utils/crc.h"
@ -41,8 +39,6 @@
#define ACOS(x) (degrees(acos(x)))
typedef HmSystem<MAX_NUM_INVERTERS> HmSystemType;
//typedef HmPayload<HmSystemType> PayloadType;
//typedef MiPayload<HmSystemType> MiPayloadType;
#ifdef ESP32
typedef CmtRadio<esp32_3wSpi> CmtRadioType;
#endif
@ -171,15 +167,6 @@ class app : public IApp, public ah::Scheduler {
mMqtt.setPowerLimitAck(iv);
}
void ivSendHighPrio(Inverter<> *iv) {
if(mIVCommunicationOn) { // only send commands if communication is enabled
//if (iv->ivGen == IV_MI)
// mMiPayload.ivSendHighPrio(iv);
//else
// mPayload.ivSendHighPrio(iv);
}
}
bool getMqttIsConnected() {
return mMqtt.isConnected();
}

2
src/appInterface.h

@ -53,8 +53,6 @@ class IApp {
virtual void setMqttDiscoveryFlag() = 0;
virtual void setMqttPowerLimitAck(Inverter<> *iv) = 0;
virtual void ivSendHighPrio(Inverter<> *iv) = 0;
virtual bool getMqttIsConnected() = 0;
virtual uint32_t getMqttRxCnt() = 0;
virtual uint32_t getMqttTxCnt() = 0;

4
src/defines.h

@ -13,7 +13,7 @@
//-------------------------------------
#define VERSION_MAJOR 0
#define VERSION_MINOR 8
#define VERSION_PATCH 0
#define VERSION_PATCH 1
//-------------------------------------
typedef struct {
@ -94,6 +94,8 @@ enum {MQTT_STATUS_OFFLINE = 0, MQTT_STATUS_PARTIAL, MQTT_STATUS_ONLINE};
#define MQTT_MAX_PACKET_SIZE 384
#define PLUGIN_DISPLAY
typedef struct {
uint32_t rxFail;
uint32_t rxFailNoAnser;

20
src/hm/CommQueue.h

@ -22,10 +22,6 @@ class CommQueue {
void add(Inverter<> *iv, uint8_t cmd, bool delOnPop = true) {
mQueue[mWrPtr] = queue_s(iv, cmd, delOnPop, false);
/*mQueue[mRdPtr].firstTry = false;
if((IV_HM == mQueue[mRdPtr].iv->ivGen) || (IV_MI == mQueue[mRdPtr].iv->ivGen)) {
mQueue[mRdPtr].firstTry = ((mQueue[mRdPtr].iv->isAvailable()) || (millis() < 120000));
}*/
inc(&mWrPtr);
}
@ -41,7 +37,6 @@ class CommQueue {
uint32_t ts;
bool delOnPop;
bool isDevControl;
//bool firstTry;
queue_s() {}
queue_s(Inverter<> *i, uint8_t c, bool d, bool dev) :
iv(i), cmd(c), attempts(5), ts(0), delOnPop(d), isDevControl(dev) {}
@ -50,10 +45,6 @@ class CommQueue {
protected:
void add(queue_s q) {
mQueue[mWrPtr] = q;
/*mQueue[mRdPtr].firstTry = false;
if((IV_HM == mQueue[mRdPtr].iv->ivGen) || (IV_MI == mQueue[mRdPtr].iv->ivGen)) {
mQueue[mRdPtr].firstTry = ((mQueue[mRdPtr].iv->isAvailable()) || (millis() < 120000));
}*/
inc(&mWrPtr);
}
@ -61,10 +52,6 @@ class CommQueue {
mQueue[mWrPtr] = *q;
if(rstAttempts)
mQueue[mWrPtr].attempts = 5;
/*mQueue[mRdPtr].firstTry = false;
if((IV_HM == mQueue[mRdPtr].iv->ivGen) || (IV_MI == mQueue[mRdPtr].iv->ivGen)) {
mQueue[mRdPtr].firstTry = ((mQueue[mRdPtr].iv->isAvailable()) || (millis() < 120000));
}*/
inc(&mWrPtr);
}
@ -89,13 +76,6 @@ class CommQueue {
inc(&mRdPtr);
}
/*bool isFirstTry(void) {
if(!mQueue[mRdPtr].firstTry)
return false;
mQueue[mRdPtr].firstTry = false;
return true;
}*/
void setTs(uint32_t *ts) {
mQueue[mRdPtr].ts = *ts;
}

49
src/hm/Communication.h

@ -9,6 +9,7 @@
#include "CommQueue.h"
#include <Arduino.h>
#include "../utils/crc.h"
#include "heuristic.h"
#define MI_TIMEOUT 250
#define DEFAULT_TIMEOUT 500
@ -52,6 +53,9 @@ class Communication : public CommQueue<> {
for(uint8_t i = 0; i < MAX_PAYLOAD_ENTRIES; i++) {
mLocalBuf[i].len = 0;
}
mHeu.printStatus(q->iv);
mHeu.getTxCh(q->iv);
mState = States::START;
break;
@ -84,6 +88,7 @@ class Communication : public CommQueue<> {
DBGPRINTLN(F("ms"));
q->iv->radioStatistics.rxFailNoAnser++; // got nothing
mHeu.setGotNothing(q->iv);
if((IV_HMS == q->iv->ivGen) || (IV_HMT == q->iv->ivGen)) {
q->iv->radio->switchFrequency(q->iv, HOY_BOOT_FREQ_KHZ, WORK_FREQ_KHZ);
mWaitTimeout = millis() + 1000;
@ -135,7 +140,8 @@ class Communication : public CommQueue<> {
yield();
}
if(0 == q->attempts) {
//cmdDone(q);
mHeu.setGotFragment(q->iv);
q->iv->radioStatistics.rxFail++; // got no complete payload
cmdDone(true);
mState = States::RESET;
} else
@ -160,17 +166,7 @@ class Communication : public CommQueue<> {
i++;
}
if(q->attempts) {
q->iv->radio->sendCmdPacket(q->iv, TX_REQ_INFO, (SINGLE_FRAME + i), true);
q->iv->radioStatistics.retransmits++;
mWaitTimeout = millis() + SINGLEFR_TIMEOUT; // timeout
mState = States::WAIT;
} else {
add(q, true);
//cmdDone(q);
cmdDone(true);
mState = States::RESET;
}
sendRetransmit(q, i);
return;
}
@ -185,21 +181,12 @@ class Communication : public CommQueue<> {
DBGPRINT(String(q->attempts));
DBGPRINTLN(F(" attempts left)"));
if(q->attempts) {
q->iv->radio->sendCmdPacket(q->iv, TX_REQ_INFO, (SINGLE_FRAME + i), true);
q->iv->radioStatistics.retransmits++;
mWaitTimeout = millis() + SINGLEFR_TIMEOUT; // timeout;
mState = States::WAIT;
} else {
add(q, true);
//cmdDone(q);
cmdDone(true);
mState = States::RESET;
}
sendRetransmit(q, i);
return;
}
}
mHeu.setGotAll(q->iv);
compilePayload(q);
if(NULL != mCbPayload)
@ -376,6 +363,21 @@ class Communication : public CommQueue<> {
}
}
void sendRetransmit(const queue_s *q, uint8_t i) {
if(q->attempts) {
q->iv->radio->sendCmdPacket(q->iv, TX_REQ_INFO, (SINGLE_FRAME + i), true);
q->iv->radioStatistics.retransmits++;
mWaitTimeout = millis() + SINGLEFR_TIMEOUT; // timeout
mState = States::WAIT;
} else {
mHeu.setGotFragment(q->iv);
q->iv->radioStatistics.rxFail++; // got no complete payload
add(q, true);
cmdDone(true);
mState = States::RESET;
}
}
private:
inline void miHwDecode(packet_t *p, const queue_s *q) {
record_t<> *rec = q->iv->getRecordStruct(InverterDevInform_All); // choose the record structure
@ -714,6 +716,7 @@ class Communication : public CommQueue<> {
uint8_t mPayload[MAX_BUFFER];
payloadListenerType mCbPayload = NULL;
alarmListenerType mCbAlarm = NULL;
Heuristic mHeu;
};
#endif /*__COMMUNICATION_H__*/

117
src/hm/Heuristic.h

@ -7,6 +7,7 @@
#define __HEURISTIC_H__
#include "../utils/dbg.h"
#include "hmInverter.h"
#define RF_MAX_CHANNEL_ID 5
#define RF_MAX_QUALITY 4
@ -14,96 +15,58 @@
class Heuristic {
public:
void setup() {
uint8_t j;
for(uint8_t i = 0; i < RF_MAX_CHANNEL_ID; i++) {
mTxQuality[i] = -6; // worst
for(j = 0; j < 10; j++) {
mRxCh[i][j] = 3;
}
}
}
/*uint8_t getRxCh(void) {
uint8_t getTxCh(Inverter<> *iv) {
if((IV_HMS == iv->ivGen) || (IV_HMT == iv->ivGen))
return 0; // not used for these inverter types
}*/
uint8_t getTxCh(void) {
if(++mCycleCnt > RF_MAX_CHANNEL_ID) {
bool ok = false;
for(uint8_t i = 0; i < RF_MAX_CHANNEL_ID; i++) {
if(mTxQuality[i] > -4) {
ok = true;
mState = States::RUNNING;
}
}
if(!ok) { // restart
mCycleCnt = 0;
mState = States::TRAINING;
uint8_t id = 0;
int8_t bestQuality = -6;
for(uint8_t i = 0; i < RF_MAX_CHANNEL_ID; i++) {
if(iv->txRfQuality[i] > bestQuality) {
bestQuality = iv->txRfQuality[i];
id = i;
}
}
if(bestQuality > -6)
iv->txRfChId = (iv->txRfChId + 1) % RF_MAX_CHANNEL_ID; // next channel
else
iv->txRfChId = id; // best quality channel
if(States::TRAINING == mState) {
mTxChId = (mTxChId + 1) % RF_MAX_CHANNEL_ID;
return id2Ch(mTxChId);
} else {
int8_t bestQuality = -6;
uint8_t id = 0;
for(uint8_t i = 0; i < RF_MAX_CHANNEL_ID; i++) {
if((mCycleCnt % 50) == 0) {
if(mTxQuality[(i + mTxChId) % RF_MAX_CHANNEL_ID] != -6) {
id = i;
break;
}
}
if(mTxQuality[(i + mTxChId) % RF_MAX_CHANNEL_ID] == 4) {
id = i;
break;
}
if(mTxQuality[i] > bestQuality) {
bestQuality = mTxQuality[i];
id = i;
}
}
mTxChId = id;
return id2Ch(mTxChId);
}
return id2Ch(iv->txRfChId);
}
void setGotAll(void) {
updateQuality(2); // GOOD
void setGotAll(Inverter<> *iv) {
updateQuality(iv, 2); // GOOD
}
void setGotFragment(void) {
updateQuality(1); // OK
void setGotFragment(Inverter<> *iv) {
updateQuality(iv, 1); // OK
}
void setGotNothing(void) {
updateQuality(-2); // BAD
void setGotNothing(Inverter<> *iv) {
updateQuality(iv, -2); // BAD
}
void printStatus(void) {
DPRINT(DBG_INFO, F("Status: #"));
DBGPRINT(String(mCycleCnt));
void printStatus(Inverter<> *iv) {
DPRINT(DBG_INFO, F("Status:"));
DBGPRINT(F(" |"));
for(uint8_t i = 0; i < RF_MAX_CHANNEL_ID; i++) {
DBGPRINT(F(" "));
DBGPRINT(String(mTxQuality[i]));
DBGPRINT(String(iv->txRfQuality[i]));
}
DBGPRINTLN("");
}
private:
void updateQuality(uint8_t quality) {
mTxQuality[mTxChId] += quality;
if(mTxQuality[mTxChId] > RF_MAX_QUALITY)
mTxQuality[mTxChId] = RF_MAX_QUALITY;
else if(mTxQuality[mTxChId] < RF_MIN_QUALTIY)
mTxQuality[mTxChId] = RF_MIN_QUALTIY;
void updateQuality(Inverter<> *iv, uint8_t quality) {
iv->txRfQuality[iv->txRfChId] += quality;
if(iv->txRfQuality[iv->txRfChId] > RF_MAX_QUALITY)
iv->txRfQuality[iv->txRfChId] = RF_MAX_QUALITY;
else if(iv->txRfQuality[iv->txRfChId] < RF_MIN_QUALTIY)
iv->txRfQuality[iv->txRfChId] = RF_MIN_QUALTIY;
}
uint8_t ch2Id(uint8_t ch) {
/*uint8_t ch2Id(uint8_t ch) {
switch(ch) {
case 3: return 0;
case 23: return 1;
@ -112,9 +75,9 @@ class Heuristic {
case 75: return 4;
}
return 0; // standard
}
}*/
uint8_t id2Ch(uint8_t id) {
inline uint8_t id2Ch(uint8_t id) {
switch(id) {
case 0: return 3;
case 1: return 23;
@ -125,22 +88,8 @@ class Heuristic {
return 0; // standard
}
private:
enum class States : uint8_t {
TRAINING, RUNNING
};
private:
uint8_t mChList[5] = {03, 23, 40, 61, 75};
int8_t mTxQuality[RF_MAX_CHANNEL_ID];
uint8_t mTxChId = 0;
uint8_t mRxCh[RF_MAX_CHANNEL_ID][10];
uint8_t mRxChId = 0;
uint32_t mCycleCnt = 0;
States mState = States::TRAINING;
};

98
src/hm/hmInverter.h

@ -78,31 +78,6 @@ struct alarm_t {
alarm_t() : code(0), start(0), end(0) {}
};
class CommandAbstract {
public:
CommandAbstract(uint8_t txType = 0, uint8_t cmd = 0) {
_TxType = txType;
_Cmd = cmd;
};
virtual ~CommandAbstract() {};
uint8_t getCmd() const {
return _Cmd;
}
protected:
uint8_t _TxType;
uint8_t _Cmd;
};
class InfoCommand : public CommandAbstract {
public:
InfoCommand(uint8_t cmd){
_TxType = 0x15;
_Cmd = cmd;
}
};
// list of all available functions, mapped in hmDefines.h
template<class T=float>
const calcFunc_t<T> calcFunctions[] = {
@ -153,7 +128,8 @@ class Inverter {
int8_t rssi; // RSSI
Radio *radio; // pointer to associated radio class
statistics_t radioStatistics; // information about transmitted, failed, ... packets
int8_t txRfQuality[5]; // heuristics tx quality (check 'Heuristics.h')
uint8_t txRfChId; // RF TX channel id
static uint32_t *timestamp; // system timestamp
static cfgInst_t *generalConfig; // general inverter configuration from setup
@ -175,10 +151,7 @@ class Inverter {
alarmLastId = 0;
rssi = -127;
memset(&radioStatistics, 0, sizeof(statistics_t));
}
~Inverter() {
// TODO: cleanup
memset(txRfQuality, -6, 5);
}
void tickSend(std::function<void(uint8_t cmd, bool isDevControl)> cb) {
@ -194,7 +167,10 @@ class Inverter {
cb(InverterDevInform_Simple, false); // get hardware version
else if(actPowerLimit == 0xffff)
cb(SystemConfigPara, false); // power limit info
else
else if(InitDataState != devControlCmd) {
cb(devControlCmd, false); // custom command which was received by API
devControlCmd = InitDataState;
} else
cb(RealTimeRunData_Debug, false); // get live data
} else {
if(0 == getFwVersion())
@ -209,57 +185,6 @@ class Inverter {
}
}
/*template <typename T>
void enqueCommand(uint8_t cmd) {
_commandQueue.push(std::make_shared<T>(cmd));
DPRINT_IVID(DBG_INFO, id);
DBGPRINT(F("enqueCommand: 0x"));
DBGHEXLN(cmd);
}
void setQueuedCmdFinished() {
if (!_commandQueue.empty()) {
_commandQueue.pop();
}
}
void clearCmdQueue() {
DPRINTLN(DBG_INFO, F("clearCmdQueue"));
while (!_commandQueue.empty()) {
_commandQueue.pop();
}
}
uint8_t getQueuedCmd() {
if (_commandQueue.empty()) {
if (ivGen != IV_MI) {
if (getFwVersion() == 0)
enqueCommand<InfoCommand>(InverterDevInform_All); // firmware version
else if (getHwVersion() == 0)
enqueCommand<InfoCommand>(InverterDevInform_Simple); // hardware version
else if((alarmLastId != alarmMesIndex) && (alarmMesIndex != 0))
enqueCommand<InfoCommand>(AlarmData); // alarm not answered
enqueCommand<InfoCommand>(RealTimeRunData_Debug); // live data
} else { // if (ivGen == IV_MI){
if (getFwVersion() == 0) {
enqueCommand<InfoCommand>(InverterDevInform_All); // hard- and firmware version
} else {
record_t<> *rec = getRecordStruct(InverterDevInform_Simple);
if (getChannelFieldValue(CH0, FLD_PART_NUM, rec) == 0) {
enqueCommand<InfoCommand>(InverterDevInform_All); // hard- and firmware version for missing HW part nr, delivered by frame 1
} else {
enqueCommand<InfoCommand>( type == INV_TYPE_4CH ? 0x36 : 0x09 );
}
}
}
if ((actPowerLimit == 0xffff) && isConnected)
enqueCommand<InfoCommand>(SystemConfigPara); // power limit info
}
return _commandQueue.front().get()->getCmd();
}*/
void init(void) {
DPRINTLN(DBG_VERBOSE, F("hmInverter.h:init"));
initAssignment(&recordMeas, RealTimeRunData_Debug);
@ -318,8 +243,10 @@ class Inverter {
return isConnected;
}
void clearDevControlRequest() {
mDevControlRequest = false;
bool setDevCommand(uint8_t cmd) {
if(isConnected)
devControlCmd = cmd;
return isConnected;
}
void addValue(uint8_t pos, uint8_t buf[], record_t<> *rec) {
@ -359,11 +286,9 @@ class Inverter {
if (getPosByChFld(0, FLD_EVT, rec) == pos) {
if (alarmMesIndex < rec->record[pos]) {
alarmMesIndex = rec->record[pos];
//enqueCommand<InfoCommand>(AlarmUpdate); // What is the function of AlarmUpdate?
DPRINT(DBG_INFO, "alarm ID incremented to ");
DBGPRINTLN(String(alarmMesIndex));
//enqueCommand<InfoCommand>(AlarmData);
}
}
}
@ -740,7 +665,6 @@ class Inverter {
radioId.b[0] = 0x01;
}
//std::queue<std::shared_ptr<CommandAbstract>> _commandQueue;
bool mDevControlRequest; // true if change needed
};

494
src/hm/hmPayload.h

@ -1,494 +0,0 @@
//-----------------------------------------------------------------------------
// 2023 Ahoy, https://ahoydtu.de
// Creative Commons - https://creativecommons.org/licenses/by-nc-sa/4.0/deed
//-----------------------------------------------------------------------------
#ifndef __HM_PAYLOAD_H__
#define __HM_PAYLOAD_H__
#include "../utils/dbg.h"
#include "../utils/crc.h"
#include "../config/config.h"
#include "hmRadio.h"
#if defined(ESP32)
#include "../hms/cmt2300a.h"
#endif
#include <Arduino.h>
#define HMS_TIMEOUT_SEC 30
typedef struct {
uint8_t txCmd;
uint8_t txId;
uint32_t ts;
uint8_t data[MAX_PAYLOAD_ENTRIES][MAX_RF_PAYLOAD_SIZE];
int8_t rssi[MAX_PAYLOAD_ENTRIES];
uint8_t len[MAX_PAYLOAD_ENTRIES];
bool complete;
uint8_t maxPackId;
bool lastFound;
uint8_t retransmits;
bool requested;
bool gotFragment;
bool rxTmo;
uint32_t sendMillis;
} invPayload_t;
typedef std::function<void(uint8_t, Inverter<> *)> payloadListenerType;
typedef std::function<void(Inverter<> *)> alarmListenerType;
template<class HMSYSTEM>
class HmPayload {
public:
HmPayload() {}
void setup(IApp *app, HMSYSTEM *sys, uint32_t *timestamp) {
mApp = app;
mSys = sys;
mMaxRetrans = 5;
mTimestamp = timestamp;
for(uint8_t i = 0; i < MAX_NUM_INVERTERS; i++) {
reset(i);
mIvCmd56Cnt[i] = 0;
}
mSerialDebug = false;
mHighPrioIv = NULL;
mCbAlarm = NULL;
mCbPayload = NULL;
}
void enableSerialDebug(bool enable) {
mSerialDebug = enable;
}
void addPayloadListener(payloadListenerType cb) {
mCbPayload = cb;
}
void addAlarmListener(alarmListenerType cb) {
mCbAlarm = cb;
}
void loop() {
if (NULL != mHighPrioIv) {
ivSend(mHighPrioIv, true); // for e.g. devcontrol commands
mHighPrioIv = NULL;
}
}
/*void simulation() {
uint8_t pay[] = {
0x00, 0x01, 0x01, 0x24, 0x02, 0x28, 0x02, 0x33,
0x06, 0x49, 0x06, 0x6a, 0x00, 0x05, 0x5f, 0x1b,
0x00, 0x06, 0x66, 0x9a, 0x03, 0xfd, 0x04, 0x0b,
0x01, 0x23, 0x02, 0x28, 0x02, 0x28, 0x06, 0x41,
0x06, 0x43, 0x00, 0x05, 0xdc, 0x2c, 0x00, 0x06,
0x2e, 0x3f, 0x04, 0x01, 0x03, 0xfb, 0x09, 0x78,
0x13, 0x86, 0x18, 0x15, 0x00, 0xcf, 0x00, 0xfe,
0x03, 0xe7, 0x01, 0x42, 0x00, 0x03
};
Inverter<> *iv = mSys->getInverterByPos(0);
record_t<> *rec = iv->getRecordStruct(0x0b);
rec->ts = *mTimestamp;
for (uint8_t i = 0; i < rec->length; i++) {
iv->addValue(i, pay, rec);
yield();
}
iv->doCalculations();
notify(0x0b, iv);
}*/
void ivSendHighPrio(Inverter<> *iv) {
mHighPrioIv = iv;
}
void ivSend(Inverter<> *iv, bool highPrio = false) {
if(!highPrio) {
if (mPayload[iv->id].requested) {
if (!mPayload[iv->id].complete)
process(false); // no retransmit
if (!mPayload[iv->id].complete) {
if (mSerialDebug)
DPRINT_IVID(DBG_INFO, iv->id);
if (MAX_PAYLOAD_ENTRIES == mPayload[iv->id].maxPackId) {
iv->radioStatistics.rxFailNoAnser++; // got nothing
if (mSerialDebug)
DBGPRINTLN(F("enqueued cmd failed/timeout"));
} else {
iv->radioStatistics.rxFail++; // got fragments but not complete response
if (mSerialDebug) {
DBGPRINT(F("no complete Payload received! (retransmits: "));
DBGPRINT(String(mPayload[iv->id].retransmits));
DBGPRINTLN(F(")"));
}
}
iv->setQueuedCmdFinished(); // command failed
}
}
}
reset(iv->id, !iv->isAvailable());
mPayload[iv->id].requested = true;
yield();
if (mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINT(F("Requesting Inv SN "));
DBGPRINTLN(String(iv->config->serial.u64, HEX));
}
if (iv->getDevControlRequest()) {
if (mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINT(F("Devcontrol request 0x"));
DHEX(iv->devControlCmd);
DBGPRINT(F(" power limit "));
DBGPRINTLN(String(iv->powerLimit[0]));
}
iv->powerLimitAck = false;
iv->radio->sendControlPacket(iv, iv->devControlCmd, iv->powerLimit, false);
mPayload[iv->id].txCmd = iv->devControlCmd;
//iv->clearCmdQueue();
//iv->enqueCommand<InfoCommand>(SystemConfigPara); // read back power limit
} else {
#if defined(ESP32)
if((IV_HMS == iv->ivGen) || (IV_HMT == iv->ivGen)) {
record_t<> *rec = iv->getRecordStruct(RealTimeRunData_Debug);
if(((rec->ts + HMS_TIMEOUT_SEC) < *mTimestamp) && (mIvCmd56Cnt[iv->id] < 3)) {
iv->radio->switchFrequency(iv, HOY_BOOT_FREQ_KHZ, WORK_FREQ_KHZ);
mIvCmd56Cnt[iv->id]++;
return;
} else if(++mIvCmd56Cnt[iv->id] == 10)
mIvCmd56Cnt[iv->id] = 0;
}
#endif
uint8_t cmd = iv->getQueuedCmd();
if (mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINT(F("prepareDevInformCmd 0x"));
DBGHEXLN(cmd);
}
iv->radio->prepareDevInformCmd(iv, cmd, mPayload[iv->id].ts, iv->alarmLastId, false);
mPayload[iv->id].txCmd = cmd;
}
}
void add(Inverter<> *iv, packet_t *p) {
if (p->packet[0] == (TX_REQ_INFO + ALL_FRAMES)) { // response from get information command
mPayload[iv->id].txId = p->packet[0];
DPRINTLN(DBG_DEBUG, F("Response from info request received"));
uint8_t *pid = &p->packet[9];
if (*pid == 0x00) {
DPRINTLN(DBG_DEBUG, F("fragment number zero received and ignored"));
} else {
DPRINT(DBG_DEBUG, F("PID: 0x"));
DPRINTLN(DBG_DEBUG, String(*pid, HEX));
if ((*pid & 0x7F) < MAX_PAYLOAD_ENTRIES) {
memcpy(mPayload[iv->id].data[(*pid & 0x7F) - 1], &p->packet[10], p->len - 11);
mPayload[iv->id].len[(*pid & 0x7F) - 1] = p->len - 11;
mPayload[iv->id].gotFragment = true;
mPayload[iv->id].rssi[(*pid & 0x7F) - 1] = p->rssi;
}
if ((*pid & ALL_FRAMES) == ALL_FRAMES) {
// Last packet
if (((*pid & 0x7f) > mPayload[iv->id].maxPackId) || (MAX_PAYLOAD_ENTRIES == mPayload[iv->id].maxPackId)) {
mPayload[iv->id].maxPackId = (*pid & 0x7f);
if (*pid > 0x81)
mPayload[iv->id].lastFound = true;
}
}
}
} else if (p->packet[0] == (TX_REQ_DEVCONTROL + ALL_FRAMES)) { // response from dev control command
DPRINTLN(DBG_DEBUG, F("Response from devcontrol request received"));
mPayload[iv->id].txId = p->packet[0];
iv->clearDevControlRequest();
if ((p->packet[12] == ActivePowerContr) && (p->packet[13] == 0x00)) {
bool ok = true;
if((p->packet[10] == 0x00) && (p->packet[11] == 0x00)) {
mApp->setMqttPowerLimitAck(iv);
iv->powerLimitAck = true;
} else
ok = false;
if (mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINT(F(" has "));
if(!ok) DBGPRINT(F("not "));
DBGPRINT(F("accepted power limit set point "));
DBGPRINT(String(iv->powerLimit[0]));
DBGPRINT(F(" with PowerLimitControl "));
DBGPRINTLN(String(iv->powerLimit[1]));
}
iv->clearCmdQueue();
iv->enqueCommand<InfoCommand>(SystemConfigPara); // read back power limit
if(mHighPrioIv == NULL) // do it immediately if possible
mHighPrioIv = iv;
}
iv->devControlCmd = Init;
}
}
void process(bool retransmit) {
for (uint8_t id = 0; id < mSys->getNumInverters(); id++) {
Inverter<> *iv = mSys->getInverterByPos(id);
if (NULL == iv)
continue; // skip to next inverter
if ((mPayload[iv->id].txId != (TX_REQ_INFO + ALL_FRAMES)) && (0 != mPayload[iv->id].txId)) {
// no processing needed if txId is not 0x95
mPayload[iv->id].complete = true;
continue; // skip to next inverter
}
if((IV_HMS == iv->ivGen) || (IV_HMT == iv->ivGen)) {
if((mPayload[iv->id].sendMillis + 400) > millis())
return; // to fast, wait until packets are received!
}
if (!mPayload[iv->id].complete) {
bool crcPass, pyldComplete, fastNext;
crcPass = build(iv, &pyldComplete, &fastNext);
if (!crcPass && !pyldComplete) { // payload not complete
if ((mPayload[iv->id].requested) && (retransmit)) {
if (mPayload[iv->id].retransmits < mMaxRetrans) {
mPayload[iv->id].retransmits++;
if (iv->devControlCmd == Restart || iv->devControlCmd == CleanState_LockAndAlarm) {
// This is required to prevent retransmissions without answer.
DPRINTLN(DBG_INFO, F("Prevent retransmit on Restart / CleanState_LockAndAlarm..."));
mPayload[iv->id].retransmits = mMaxRetrans;
} else if(iv->devControlCmd == ActivePowerContr) {
DPRINT_IVID(DBG_INFO, iv->id);
DPRINTLN(DBG_INFO, F("retransmit power limit"));
iv->radio->sendControlPacket(iv, iv->devControlCmd, iv->powerLimit, true);
} else {
if(false == mPayload[iv->id].gotFragment) {
DPRINT_IVID(DBG_WARN, iv->id);
if (mPayload[iv->id].rxTmo) {
DBGPRINTLN(F("nothing received"));
mPayload[iv->id].retransmits = mMaxRetrans;
} else {
DBGPRINTLN(F("nothing received: complete retransmit"));
mPayload[iv->id].txCmd = iv->getQueuedCmd();
DPRINTLN(DBG_INFO, F("(#") + String(iv->id) + F(") prepareDevInformCmd 0x") + String(mPayload[iv->id].txCmd, HEX));
iv->radio->prepareDevInformCmd(iv, mPayload[iv->id].txCmd, mPayload[iv->id].ts, iv->alarmMesIndex, true);
}
} else {
for (uint8_t i = 0; i < (mPayload[iv->id].maxPackId - 1); i++) {
if (mPayload[iv->id].len[i] == 0) {
if (mSerialDebug) {
DPRINT_IVID(DBG_WARN, iv->id);
DBGPRINT(F("Frame "));
DBGPRINT(String(i + 1));
DBGPRINTLN(F(" missing: Request Retransmit"));
}
iv->radio->sendCmdPacket(iv, TX_REQ_INFO, (SINGLE_FRAME + i), true);
break; // only request retransmit one frame per loop
}
yield();
}
}
}
}
} else if (false == mPayload[iv->id].gotFragment) {
// only if there is no sign of life
mPayload[iv->id].rxTmo = true; // inv might be down, no complete retransmit anymore
}
} else if(!crcPass && pyldComplete) { // crc error on complete Payload
if (mPayload[iv->id].retransmits < mMaxRetrans) {
mPayload[iv->id].retransmits++;
mPayload[iv->id].txCmd = iv->getQueuedCmd();
if (mSerialDebug) {
DPRINT_IVID(DBG_WARN, iv->id);
DBGPRINTLN(F("CRC Error: Request Complete Retransmit"));
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINT(F("prepareDevInformCmd 0x"));
DBGHEXLN(mPayload[iv->id].txCmd);
}
iv->radio->prepareDevInformCmd(iv, mPayload[iv->id].txCmd, mPayload[iv->id].ts, iv->alarmLastId, true);
}
} else { // payload complete
if (mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINT(F("procPyld: cmd: 0x"));
DBGHEXLN(mPayload[iv->id].txCmd);
//DPRINT(DBG_DEBUG, F("procPyld: txid: 0x"));
//DBGHEXLN(mPayload[iv->id].txId);
DPRINT(DBG_DEBUG, F("procPyld: max: "));
DPRINTLN(DBG_DEBUG, String(mPayload[iv->id].maxPackId));
}
record_t<> *rec = iv->getRecordStruct(mPayload[iv->id].txCmd); // choose the parser
mPayload[iv->id].complete = true;
mPayload[iv->id].requested = false;
mPayload[iv->id].rxTmo = false;
uint8_t payload[MAX_BUFFER];
uint8_t payloadLen = 0;
memset(payload, 0, MAX_BUFFER);
int8_t rssi = -127;
for (uint8_t i = 0; i < (mPayload[iv->id].maxPackId); i++) {
if((mPayload[iv->id].len[i] + payloadLen) > MAX_BUFFER) {
DPRINTLN(DBG_ERROR, F("payload buffer to small!"));
break;
}
memcpy(&payload[payloadLen], mPayload[iv->id].data[i], (mPayload[iv->id].len[i]));
payloadLen += (mPayload[iv->id].len[i]);
// get worst RSSI
if(mPayload[iv->id].rssi[i] > rssi)
rssi = mPayload[iv->id].rssi[i];
yield();
}
payloadLen -= 2;
if (mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINT(F("Payload ("));
DBGPRINT(String(payloadLen));
DBGPRINT(F("): "));
ah::dumpBuf(payload, payloadLen);
}
if (NULL == rec) {
DPRINTLN(DBG_ERROR, F("record is NULL!"));
} else if ((rec->pyldLen == payloadLen) || (0 == rec->pyldLen)) {
if (mPayload[iv->id].txId == (TX_REQ_INFO + ALL_FRAMES))
iv->radioStatistics.rxSuccess++;
rec->ts = mPayload[iv->id].ts;
for (uint8_t i = 0; i < rec->length; i++) {
iv->addValue(i, payload, rec);
yield();
}
iv->rssi = rssi;
iv->doCalculations();
notify(mPayload[iv->id].txCmd, iv);
if(AlarmData == mPayload[iv->id].txCmd) {
uint8_t i = 0;
while(1) {
if(0 == iv->parseAlarmLog(i++, payload, payloadLen))
break;
if (NULL != mCbAlarm)
(mCbAlarm)(iv);
yield();
}
}
if (fastNext && (mHighPrioIv == NULL)) {
/*iv->setQueuedCmdFinished();
uint8_t cmd = iv->getQueuedCmd();
if (mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINT(F("fast mode "));
DBGPRINT(F("prepareDevInformCmd 0x"));
DBGHEXLN(cmd);
}
iv->radioStatistics.rxSuccess++;
iv->radio->prepareDevInformCmd(iv, cmd, mPayload[iv->id].ts, iv->alarmLastId, false);
mPayload[iv->id].txCmd = cmd;
*/
mHighPrioIv = iv;
}
} else {
if (mSerialDebug) {
DPRINT(DBG_ERROR, F("plausibility check failed, expected "));
DBGPRINT(String(rec->pyldLen));
DBGPRINTLN(F(" bytes"));
}
iv->radioStatistics.rxFail++;
}
iv->setQueuedCmdFinished();
}
}
yield();
}
}
private:
void notify(uint8_t val, Inverter<> *iv) {
if(NULL != mCbPayload)
(mCbPayload)(val, iv);
}
bool build(Inverter<> *iv, bool *complete, bool *fastNext ) {
DPRINTLN(DBG_VERBOSE, F("build"));
uint16_t crc = 0xffff, crcRcv = 0x0000;
if (mPayload[iv->id].maxPackId > MAX_PAYLOAD_ENTRIES)
mPayload[iv->id].maxPackId = MAX_PAYLOAD_ENTRIES;
// check if all fragments are there
*complete = true;
*fastNext = false;
for (uint8_t i = 0; i < mPayload[iv->id].maxPackId; i++) {
if(mPayload[iv->id].len[i] == 0) {
*complete = false;
}
}
if(!*complete)
return false;
for (uint8_t i = 0; i < mPayload[iv->id].maxPackId; i++) {
if (mPayload[iv->id].len[i] > 0) {
if (i == (mPayload[iv->id].maxPackId - 1)) {
crc = ah::crc16(mPayload[iv->id].data[i], mPayload[iv->id].len[i] - 2, crc);
crcRcv = (mPayload[iv->id].data[i][mPayload[iv->id].len[i] - 2] << 8) | (mPayload[iv->id].data[i][mPayload[iv->id].len[i] - 1]);
} else
crc = ah::crc16(mPayload[iv->id].data[i], mPayload[iv->id].len[i], crc);
}
yield();
}
//return (crc == crcRcv) ? true : false;
if (crc != crcRcv)
return false;
//requests to cause the next request to be executed immediately
if (mPayload[iv->id].gotFragment && ((mPayload[iv->id].txCmd < RealTimeRunData_Debug) || (mPayload[iv->id].txCmd >= AlarmData))) {
*fastNext = true;
}
return true;
}
void reset(uint8_t id, bool setTxTmo = true) {
//DPRINT_IVID(DBG_INFO, id);
//DBGPRINTLN(F("resetPayload"));
memset(mPayload[id].len, 0, MAX_PAYLOAD_ENTRIES);
mPayload[id].txCmd = 0;
mPayload[id].gotFragment = false;
mPayload[id].retransmits = 0;
mPayload[id].maxPackId = MAX_PAYLOAD_ENTRIES;
mPayload[id].lastFound = false;
mPayload[id].complete = false;
mPayload[id].requested = false;
mPayload[id].ts = *mTimestamp;
mPayload[id].rxTmo = setTxTmo; // design: don't start with complete retransmit
mPayload[id].sendMillis = millis();
}
IApp *mApp;
HMSYSTEM *mSys;
uint8_t mMaxRetrans;
uint32_t *mTimestamp;
invPayload_t mPayload[MAX_NUM_INVERTERS];
uint8_t mIvCmd56Cnt[MAX_NUM_INVERTERS];
bool mSerialDebug;
Inverter<> *mHighPrioIv;
alarmListenerType mCbAlarm;
payloadListenerType mCbPayload;
};
#endif /*__HM_PAYLOAD_H__*/

40
src/hm/hmRadio.h

@ -9,7 +9,6 @@
#include <RF24.h>
#include "SPI.h"
#include "radio.h"
#include "heuristic.h"
#define SPI_SPEED 1000000
@ -41,18 +40,6 @@ class HmRadio : public Radio {
}
mDtuSn = DTU_SN;
// Depending on the program, the module can work on 2403, 2423, 2440, 2461 or 2475MHz.
// Channel List 2403, 2423, 2440, 2461, 2475MHz
mRfChLst[0] = 03;
mRfChLst[1] = 23;
mRfChLst[2] = 40;
mRfChLst[3] = 61;
mRfChLst[4] = 75;
// default channels
mTxChIdx = 2; // Start TX with 40
mRxChIdx = 0; // Start RX with 03
mSerialDebug = false;
mIrqRcvd = false;
}
@ -78,8 +65,6 @@ class HmRadio : public Radio {
mSpi->begin();
#endif
mHeu.setup();
mNrf24.begin(mSpi, ce, cs);
mNrf24.setRetries(3, 15); // 3*250us + 250us and 15 loops -> 15ms
@ -123,6 +108,9 @@ class HmRadio : public Radio {
mNrf24.setChannel(mRfChLst[mRxChIdx]);
mNrf24.startListening();
if(NULL == mLastIv) // prevent reading on NULL object!
return;
uint32_t startMicros = micros() + 5110;
uint32_t loopMillis = millis() + 400;
while (millis() < loopMillis) {
@ -130,12 +118,9 @@ class HmRadio : public Radio {
if (mIrqRcvd) {
mIrqRcvd = false;
if (getReceived()) { // everything received
mHeu.setGotAll();
if (getReceived()) { // everything received
return;
} else
mHeu.setGotFragment();
}
}
yield();
}
@ -148,10 +133,7 @@ class HmRadio : public Radio {
// not finished but time is over
if(++mRxChIdx >= RF_CHANNELS)
mRxChIdx = 0;
if(mBufCtrl.empty())
mHeu.setGotNothing();
mHeu.printStatus();
return;
}
@ -290,7 +272,7 @@ class HmRadio : public Radio {
updateCrcs(&len, appendCrc16);
// set TX and RX channels
mTxChIdx = mHeu.getTxCh();
mTxChIdx = mRfChLst[iv->txRfChId];
if(mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id);
@ -307,6 +289,8 @@ class HmRadio : public Radio {
mNrf24.openWritingPipe(reinterpret_cast<uint8_t*>(&iv->radioId.u64));
mNrf24.startWrite(mTxBuf, len, false); // false = request ACK response
mMillis = millis();
mLastIv = iv;
}
uint64_t getIvId(Inverter<> *iv) {
@ -318,14 +302,14 @@ class HmRadio : public Radio {
}
uint64_t DTU_RADIO_ID;
uint8_t mRfChLst[RF_CHANNELS];
uint8_t mTxChIdx;
uint8_t mRxChIdx;
uint8_t mRfChLst[RF_CHANNELS] = {03, 23, 40, 61, 75}; // channel List:2403, 2423, 2440, 2461, 2475MHz
uint8_t mTxChIdx = 0;
uint8_t mRxChIdx = 0;
uint32_t mMillis;
SPIClass* mSpi;
RF24 mNrf24;
Heuristic mHeu;
Inverter<> *mLastIv = NULL;
};
#endif /*__HM_RADIO_H__*/

844
src/hm/miPayload.h

@ -1,844 +0,0 @@
//-----------------------------------------------------------------------------
// 2023 Ahoy, https://ahoydtu.de
// Creative Commons - https://creativecommons.org/licenses/by-nc-sa/4.0/deed
//-----------------------------------------------------------------------------
#ifndef __MI_PAYLOAD_H__
#define __MI_PAYLOAD_H__
#include "../utils/dbg.h"
#include "../utils/crc.h"
#include "../config/config.h"
#include <Arduino.h>
#define MI_REQ_CH1 0x09
#define MI_REQ_CH2 0x11
#define MI_REQ_4CH 0x36
typedef struct {
uint32_t ts;
bool requested;
bool limitrequested;
uint8_t txCmd;
uint8_t len[MAX_PAYLOAD_ENTRIES];
int8_t rssi[4];
bool complete;
bool dataAB[3];
bool stsAB[3];
uint16_t sts[5];
uint8_t txId;
uint8_t invId;
uint8_t retransmits;
bool gotFragment;
bool gotGPF;
uint8_t rtrRes; // for limiting resets
uint8_t multi_parts; // for quality
bool rxTmo;
} miPayload_t;
typedef std::function<void(uint8_t, Inverter<> *)> miPayloadListenerType;
template<class HMSYSTEM>
class MiPayload {
public:
MiPayload() {}
void setup(IApp *app, HMSYSTEM *sys, uint32_t *timestamp) {
mApp = app;
mSys = sys;
mMaxRetrans = 5;
mTimestamp = timestamp;
for(uint8_t i = 0; i < MAX_NUM_INVERTERS; i++) {
reset(i, false, true);
mPayload[i].limitrequested = false;
mPayload[i].gotGPF = false;
}
mSerialDebug = false;
mHighPrioIv = NULL;
mCbPayload = NULL;
}
void enableSerialDebug(bool enable) {
mSerialDebug = enable;
}
void addPayloadListener(miPayloadListenerType cb) {
mCbPayload = cb;
}
void addAlarmListener(alarmListenerType cb) {
mCbAlarm = cb;
}
void loop() {
if (NULL != mHighPrioIv) {
ivSend(mHighPrioIv, true); // for e.g. devcontrol commands
mHighPrioIv = NULL;
}
}
void ivSendHighPrio(Inverter<> *iv) {
mHighPrioIv = iv;
}
void ivSend(Inverter<> *iv, bool highPrio = false) {
if(!highPrio) {
if (mPayload[iv->id].requested) {
if (!mPayload[iv->id].complete)
process(false); // no retransmit
if (!mPayload[iv->id].complete && mPayload[iv->id].rxTmo) {
if (mSerialDebug)
DPRINT_IVID(DBG_INFO, iv->id);
if (!mPayload[iv->id].gotFragment) {
iv->radioStatistics.rxFailNoAnser++; // got nothing
if (mSerialDebug)
DBGPRINTLN(F("enqueued cmd failed/timeout"));
} else {
iv->radioStatistics.rxFail++; // got "fragments" (part of the required messages)
// but no complete set of responses
if (mSerialDebug) {
DBGPRINT(F("no complete Payload received! (retransmits: "));
DBGPRINT(String(mPayload[iv->id].retransmits));
DBGPRINTLN(F(")"));
}
}
mPayload[iv->id].rxTmo = true;
mPayload[iv->id].complete = true;
iv->setQueuedCmdFinished(); // command failed
}
}
}
reset(iv->id, !iv->isAvailable());
mPayload[iv->id].requested = true;
yield();
if (mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINT(F("Requesting Inv SN "));
DBGPRINTLN(String(iv->config->serial.u64, HEX));
}
if (iv->getDevControlRequest()) {
if (mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINT(F("Devcontrol request 0x"));
DHEX(iv->devControlCmd);
DBGPRINT(F(" power limit "));
DBGPRINT(String(iv->powerLimit[0]));
DBGPRINT(F(" with PowerLimitControl "));
DBGPRINTLN(String(iv->powerLimit[1]));
}
iv->powerLimitAck = false;
iv->radio->sendControlPacket(iv, iv->devControlCmd, iv->powerLimit, false, false, (iv->powerLimit[1] == RelativNonPersistent) ? 0 : iv->getMaxPower());
mPayload[iv->id].txCmd = iv->devControlCmd;
mPayload[iv->id].limitrequested = true;
iv->clearCmdQueue();
} else {
uint8_t cmd = iv->getQueuedCmd();
uint8_t cmd2 = cmd;
if ( cmd == SystemConfigPara ) { //0x05 for HM-types
if (!mPayload[iv->id].gotGPF) {
iv->setQueuedCmdFinished();
cmd = iv->getQueuedCmd();
}
}
if (cmd == 0x01) { //0x1 for HM-types
cmd2 = 0x00;
cmd = 0x0f; // for MI, these seem to make part of polling the device software and hardware version number command
} else if (cmd == SystemConfigPara ) { // 0x05 for HM-types
cmd2 = 0x00;
cmd = 0x10; // legacy GPF request
}
if (mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINT(F("legacy cmd 0x"));
DBGHEXLN(cmd);
}
iv->radio->sendCmdPacket(iv, cmd, cmd2, false, false);
mPayload[iv->id].txCmd = cmd;
if (iv->type == INV_TYPE_1CH || iv->type == INV_TYPE_2CH) {
mPayload[iv->id].dataAB[CH1] = false;
mPayload[iv->id].stsAB[CH1] = false;
mPayload[iv->id].dataAB[CH0] = false;
mPayload[iv->id].stsAB[CH0] = false;
if (iv->type == INV_TYPE_2CH) {
mPayload[iv->id].dataAB[CH2] = false;
mPayload[iv->id].stsAB[CH2] = false;
}
}
}
}
void add(Inverter<> *iv, packet_t *p) {
//DPRINTLN(DBG_INFO, F("MI got data [0]=") + String(p->packet[0], HEX));
if (p->packet[0] == (0x88)) { // 0x88 is MI status response to 0x09
miStsDecode(iv, p);
}
else if (p->packet[0] == (MI_REQ_CH2 + SINGLE_FRAME)) { // 0x92; MI status response to 0x11
miStsDecode(iv, p, CH2);
} else if ( p->packet[0] == MI_REQ_CH1 + ALL_FRAMES ||
p->packet[0] == MI_REQ_CH2 + ALL_FRAMES ||
( p->packet[0] >= (MI_REQ_4CH + ALL_FRAMES) && p->packet[0] < (0x39 + SINGLE_FRAME)
&& mPayload[iv->id].txCmd != 0x0f) ) { // small MI or MI 1500 data responses to 0x09, 0x11, 0x36, 0x37, 0x38 and 0x39
mPayload[iv->id].txId = p->packet[0];
miDataDecode(iv,p);
} else if (p->packet[0] == ( 0x0f + ALL_FRAMES)) {
// MI response from get hardware information request
miHwDecode(iv, p);
mPayload[iv->id].txId = p->packet[0];
} else if (p->packet[0] == ( 0x10 + ALL_FRAMES)) {
// MI response from get Grid Profile information request
miGPFDecode(iv, p);
mPayload[iv->id].txId = p->packet[0];
} else if ( p->packet[0] == (TX_REQ_INFO + ALL_FRAMES) // response from get information command
|| (p->packet[0] == 0xB6 && mPayload[iv->id].txCmd != MI_REQ_4CH)) { // strange short response from MI-1500 3rd gen; might be misleading!
// atm, we just do nothing else than print out what we got...
// for decoding see xls- Data collection instructions - #147ff
//mPayload[iv->id].txId = p->packet[0];
DPRINTLN(DBG_DEBUG, F("Response from info request received"));
uint8_t *pid = &p->packet[9];
if (*pid == 0x00) {
DPRINT(DBG_DEBUG, F("fragment number zero received"));
iv->setQueuedCmdFinished();
} else if (p->packet[9] == 0x81) { // might need some additional check, as this is only meant for short answers!
DPRINT_IVID(DBG_WARN, iv->id);
DBGPRINTLN(F("seems to use 3rd gen. protocol - switching ivGen!"));
iv->ivGen = IV_HM;
iv->setQueuedCmdFinished();
iv->clearCmdQueue();
}
} else if (p->packet[0] == (TX_REQ_DEVCONTROL + ALL_FRAMES ) // response from dev control command
|| p->packet[0] == (TX_REQ_DEVCONTROL + ALL_FRAMES -1)) { // response from DRED instruction
#if DEBUG_LEVEL >= DBG_DEBUG
if (mSerialDebug) {
DPRINT_IVID(DBG_DEBUG, iv->id);
DBGPRINTLN(F("Response from devcontrol request received"));
}
#endif
mPayload[iv->id].txId = p->packet[0];
iv->clearDevControlRequest();
if ((p->packet[9] == 0x5a) && (p->packet[10] == 0x5a)) {
mApp->setMqttPowerLimitAck(iv);
iv->powerLimitAck = true;
if (mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINT(F("has accepted power limit set point "));
DBGPRINT(String(iv->powerLimit[0]));
DBGPRINT(F(" with PowerLimitControl "));
DBGPRINTLN(String(iv->powerLimit[1]));
}
iv->clearCmdQueue();
//does not work for MI
//iv->enqueCommand<InfoCommand>(SystemConfigPara); // read back power limit
}
iv->devControlCmd = Init;
} else { // some other response; copied from hmPayload:process; might not be correct to do that here!!!
if (mSerialDebug) {
DPRINT_IVID(DBG_INFO,iv->id);
DBGPRINT(F("procPyld: cmd: 0x"));
DBGHEXLN(mPayload[iv->id].txCmd);
DPRINT_IVID(DBG_INFO,iv->id);
DBGPRINT(F("procPyld: txid: 0x"));
DBGHEXLN(mPayload[iv->id].txId);
}
record_t<> *rec = iv->getRecordStruct(mPayload[iv->id].txCmd); // choose the parser
mPayload[iv->id].complete = true;
uint8_t payload[128];
uint8_t payloadLen = 0;
memset(payload, 0, 128);
payloadLen -= 2;
if (mSerialDebug) {
DPRINT(DBG_INFO, F("Payload ("));
DBGPRINT(String(payloadLen));
DBGPRINT("): ");
ah::dumpBuf(payload, payloadLen);
}
if (NULL == rec) {
DPRINTLN(DBG_ERROR, F("record is NULL!"));
} else if ((rec->pyldLen == payloadLen) || (0 == rec->pyldLen)) {
if (mPayload[iv->id].txId == (TX_REQ_INFO + ALL_FRAMES))
iv->radioStatistics.rxSuccess++;
rec->ts = mPayload[iv->id].ts;
for (uint8_t i = 0; i < rec->length; i++) {
iv->addValue(i, payload, rec);
yield();
}
iv->doCalculations();
notify(mPayload[iv->id].txCmd, iv);
if(AlarmData == mPayload[iv->id].txCmd) {
uint8_t i = 0;
while(1) {
if(0 == iv->parseAlarmLog(i++, payload, payloadLen))
break;
if (NULL != mCbAlarm)
(mCbAlarm)(iv);
yield();
}
}
} else {
DPRINTLN(DBG_ERROR, F("plausibility check failed, expected ") + String(rec->pyldLen) + F(" bytes"));
iv->radioStatistics.rxFail++;
}
iv->setQueuedCmdFinished();
}
}
void process(bool retransmit) {
for (uint8_t id = 0; id < mSys->getNumInverters(); id++) {
Inverter<> *iv = mSys->getInverterByPos(id);
if (NULL == iv)
continue; // skip to next inverter
if (IV_MI != iv->ivGen) // only process MI inverters
continue; // skip to next inverter
if ( !mPayload[iv->id].complete &&
(mPayload[iv->id].txId != (TX_REQ_INFO + ALL_FRAMES)) &&
(mPayload[iv->id].txId < (MI_REQ_4CH + ALL_FRAMES)) &&
(mPayload[iv->id].txId > (0x39 + ALL_FRAMES)) &&
(mPayload[iv->id].txId != (MI_REQ_CH1 + ALL_FRAMES)) &&
(mPayload[iv->id].txId != (MI_REQ_CH2 + ALL_FRAMES)) &&
(mPayload[iv->id].txId != (0x88)) &&
(mPayload[iv->id].txId != (0x92)) &&
(mPayload[iv->id].txId != 0) &&
mPayload[iv->id].txCmd != 0x0f &&
!iv->getDevControlRequest()) {
// no processing needed if txId is not one of 0x95, 0x88, 0x89, 0x91, 0x92 or response to 0x36ff
mPayload[iv->id].complete = true;
mPayload[iv->id].rxTmo = true;
continue; // skip to next inverter
}
if (!mPayload[iv->id].complete) {
bool gotAllMsgParts, pyldComplete, fastNext;
gotAllMsgParts = build(iv, &pyldComplete, &fastNext);
if (!gotAllMsgParts && !pyldComplete) { // payload not complete
if ((mPayload[iv->id].requested) && (retransmit)) {
if (iv->devControlCmd == Restart || iv->devControlCmd == CleanState_LockAndAlarm) {
// This is required to prevent retransmissions without answer.
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINTLN(F("Prevent retransmit on Restart / CleanState_LockAndAlarm..."));
mPayload[iv->id].retransmits = mMaxRetrans;
mPayload[iv->id].rxTmo = true;
} else if(iv->devControlCmd == ActivePowerContr) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINTLN(F("retransmit power limit"));
iv->radio->sendControlPacket(iv, iv->devControlCmd, iv->powerLimit, true, false, (iv->powerLimit[1] == RelativNonPersistent) ? 0 : iv->getMaxPower());
} else {
uint8_t cmd = mPayload[iv->id].txCmd;
if (mPayload[iv->id].retransmits < mMaxRetrans) {
mPayload[iv->id].retransmits++;
if( !mPayload[iv->id].gotFragment && mPayload[iv->id].rxTmo ) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINTLN(F("nothing received"));
mPayload[iv->id].retransmits = mMaxRetrans;
mPayload[iv->id].requested = false; //close failed request
} else if( !mPayload[iv->id].gotFragment && !mPayload[iv->id].rxTmo ) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINTLN(F("retransmit on failed first request"));
mPayload[iv->id].rxTmo = true;
iv->radio->sendCmdPacket(iv, cmd, cmd, true, false);
} else if ( cmd == 0x0f ) {
//hard/firmware request
iv->radio->sendCmdPacket(iv, 0x0f, 0x00, true, false);
mPayload[id].multi_parts = 0;
} else {
bool change = false;
if ( cmd >= MI_REQ_4CH && cmd < 0x39 ) { // MI-1500 Data command
if (cmd > MI_REQ_4CH && mPayload[iv->id].retransmits==1) // first request for the upper channels
change = true;
} else if ( cmd == MI_REQ_CH1 ) {//MI single or dual channel device
if ( mPayload[iv->id].dataAB[CH1] && iv->type == INV_TYPE_2CH ) {
if (!mPayload[iv->id].stsAB[CH1] && mPayload[iv->id].retransmits<2) {}
//first try to get missing sts for first channel a second time
else if (!mPayload[iv->id].stsAB[CH2] || !mPayload[iv->id].dataAB[CH2] ) {
cmd = MI_REQ_CH2;
change = true;
if (mPayload[iv->id].rtrRes < 3) //only get back to first channel twice
mPayload[iv->id].retransmits = 0; //reset counter
}
}
} else if ( cmd == MI_REQ_CH2) {
if ( mPayload[iv->id].dataAB[CH2] ) { // data + status ch2 are there?
if (mPayload[iv->id].stsAB[CH2] && (!mPayload[iv->id].stsAB[CH1] || !mPayload[iv->id].dataAB[CH1])) {
cmd = MI_REQ_CH1;
change = true;
}
}
}
DPRINT_IVID(DBG_INFO, iv->id);
if (change) {
DBGPRINT(F("next request is"));
mPayload[iv->id].txCmd = cmd;
mPayload[iv->id].rtrRes++;
} else {
DBGPRINT(F("sth."));
DBGPRINT(F(" missing: Request Retransmit"));
}
DBGPRINT(F(" 0x"));
DBGHEXLN(cmd);
mPayload[id].multi_parts = 0;
iv->radio->sendCmdPacket(iv, cmd, cmd, true, false);
yield();
}
} else {
mPayload[iv->id].rxTmo = true;
}
}
}
} else if(!gotAllMsgParts && pyldComplete) { // crc error on complete Payload
if (mPayload[iv->id].retransmits < mMaxRetrans) {
mPayload[iv->id].retransmits++;
mPayload[iv->id].txCmd = iv->getQueuedCmd();
mPayload[id].multi_parts = 0;
if (mSerialDebug) {
DPRINT_IVID(DBG_WARN, iv->id);
DBGPRINTLN(F("CRC Error: Request Complete Retransmit"));
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINT(F("prepareDevInformCmd 0x"));
DBGHEXLN(mPayload[iv->id].txCmd);
}
iv->radio->sendCmdPacket(iv, mPayload[iv->id].txCmd, mPayload[iv->id].txCmd, false, false);
} else {
mPayload[iv->id].rxTmo = true;
}
} else {
if (!fastNext) {
mPayload[iv->id].rxTmo = true;
} else {
if (mHighPrioIv == NULL)
mHighPrioIv = iv;
}
}
} else {
mPayload[iv->id].rxTmo = true;
}
yield();
}
}
private:
void notify(uint8_t val, Inverter<> *iv) {
if(NULL != mCbPayload)
(mCbPayload)(val, iv);
}
void miStsDecode(Inverter<> *iv, packet_t *p, uint8_t stschan = CH1) {
record_t<> *rec = iv->getRecordStruct(RealTimeRunData_Debug); // choose the record structure
rec->ts = mPayload[iv->id].ts;
mPayload[iv->id].gotFragment = true;
mPayload[iv->id].multi_parts += 3;
mPayload[iv->id].txId = p->packet[0];
miStsConsolidate(iv, stschan, rec, p->packet[10], p->packet[12], p->packet[9], p->packet[11]);
mPayload[iv->id].stsAB[stschan] = true;
if (mPayload[iv->id].stsAB[CH1] && mPayload[iv->id].stsAB[CH2])
mPayload[iv->id].stsAB[CH0] = true;
}
void miStsConsolidate(Inverter<> *iv, uint8_t stschan, record_t<> *rec, uint8_t uState, uint8_t uEnum, uint8_t lState = 0, uint8_t lEnum = 0) {
//uint8_t status = (p->packet[11] << 8) + p->packet[12];
uint16_t statusMi = 3; // regular status for MI, change to 1 later?
if ( uState == 2 ) {
statusMi = 5050 + stschan; //first approach, needs review!
if (lState)
statusMi += lState*10;
} else if ( uState > 3 ) {
statusMi = uState*1000 + uEnum*10;
if (lState)
statusMi += lState*100; //needs review, esp. for 4ch-8310 state!
//if (lEnum)
statusMi += lEnum;
if (uEnum < 6) {
statusMi += stschan;
}
if (statusMi == 8000)
statusMi = 8310; //trick?
}
uint16_t prntsts = statusMi == 3 ? 1 : statusMi;
bool stsok = true;
if ( statusMi != mPayload[iv->id].sts[stschan] ) { //sth.'s changed?
iv->alarmCnt = 1; // minimum...
//sth is or was wrong?
if ( (iv->type != INV_TYPE_1CH) && ( (statusMi != 3)
|| ((mPayload[iv->id].sts[stschan]) && (statusMi == 3) && (mPayload[iv->id].sts[stschan] != 3)))
) {
iv->lastAlarm[stschan] = alarm_t(prntsts, mPayload[iv->id].ts,0);
iv->alarmCnt = iv->type == INV_TYPE_2CH ? 3 : 5;
}
iv->alarmLastId = prntsts; //iv->alarmMesIndex;
mPayload[iv->id].sts[stschan] = statusMi;
stsok = false;
if (iv->alarmCnt > 1) { //more than one channel
for (uint8_t ch = 0; ch < (iv->alarmCnt); ++ch) { //start with 1
if (mPayload[iv->id].sts[ch] == 3) {
stsok = true;
break;
}
}
}
if (mSerialDebug) {
DPRINT(DBG_WARN, F("New state on CH"));
DBGPRINT(String(stschan)); DBGPRINT(F(" ("));
DBGPRINT(String(prntsts)); DBGPRINT(F("): "));
DBGPRINTLN(iv->getAlarmStr(prntsts));
}
}
if (!stsok) {
iv->setValue(iv->getPosByChFld(0, FLD_EVT, rec), rec, prntsts);
iv->lastAlarm[0] = alarm_t(prntsts, mPayload[iv->id].ts, 0);
}
if (iv->alarmMesIndex < rec->record[iv->getPosByChFld(0, FLD_EVT, rec)]) {
iv->alarmMesIndex = rec->record[iv->getPosByChFld(0, FLD_EVT, rec)]; // seems there's no status per channel in 3rd gen. models?!?
if (mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINT(F("alarm ID incremented to "));
DBGPRINTLN(String(iv->alarmMesIndex));
}
}
}
void miDataDecode(Inverter<> *iv, packet_t *p) {
record_t<> *rec = iv->getRecordStruct(RealTimeRunData_Debug); // choose the parser
rec->ts = mPayload[iv->id].ts;
mPayload[iv->id].gotFragment = true;
mPayload[iv->id].multi_parts += 4;
uint8_t datachan = ( p->packet[0] == (MI_REQ_CH1 + ALL_FRAMES) || p->packet[0] == (MI_REQ_4CH + ALL_FRAMES) ) ? CH1 :
( p->packet[0] == (MI_REQ_CH2 + ALL_FRAMES) || p->packet[0] == (0x37 + ALL_FRAMES) ) ? CH2 :
p->packet[0] == (0x38 + ALL_FRAMES) ? CH3 :
CH4;
// 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);
yield();
iv->setValue(iv->getPosByChFld(datachan, FLD_IDC, rec), rec, (float)((p->packet[11] << 8) + p->packet[12])/10);
yield();
iv->setValue(iv->getPosByChFld(0, FLD_UAC, rec), rec, (float)((p->packet[13] << 8) + p->packet[14])/10);
yield();
iv->setValue(iv->getPosByChFld(0, FLD_F, rec), rec, (float) ((p->packet[15] << 8) + p->packet[16])/100);
iv->setValue(iv->getPosByChFld(datachan, FLD_PDC, rec), rec, (float)((p->packet[17] << 8) + p->packet[18])/10);
yield();
iv->setValue(iv->getPosByChFld(datachan, FLD_YD, rec), rec, (float)((p->packet[19] << 8) + p->packet[20])/1);
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_IRR, rec), rec, (float) (calcIrradiation(iv, datachan)));
mPayload[iv->id].rssi[(datachan-1)] = p->rssi;
if ( datachan < 3 ) {
mPayload[iv->id].dataAB[datachan] = true;
}
if ( !mPayload[iv->id].dataAB[CH0] && mPayload[iv->id].dataAB[CH1] && mPayload[iv->id].dataAB[CH2] ) {
mPayload[iv->id].dataAB[CH0] = true;
}
if (p->packet[0] >= (MI_REQ_4CH + ALL_FRAMES) ) {
/*For MI1500:
if (MI1500) {
STAT = (uint8_t)(p->packet[25] );
FCNT = (uint8_t)(p->packet[26]);
FCODE = (uint8_t)(p->packet[27]);
}*/
miStsConsolidate(iv, datachan, rec, p->packet[23], p->packet[24]);
if (p->packet[0] < (0x39 + ALL_FRAMES) ) {
mPayload[iv->id].txCmd++;
mPayload[iv->id].retransmits = 0; // reserve retransmissions for each response
mPayload[iv->id].complete = false;
} else {
miComplete(iv);
}
}
}
void miComplete(Inverter<> *iv) {
if ( mPayload[iv->id].complete )
return; //if we got second message as well in repreated attempt
mPayload[iv->id].complete = true;
if (mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINTLN(F("got all msgs"));
}
record_t<> *rec = iv->getRecordStruct(RealTimeRunData_Debug);
iv->setValue(iv->getPosByChFld(0, FLD_YD, rec), rec, calcYieldDayCh0(iv,0));
//preliminary AC calculation...
float ac_pow = 0;
for(uint8_t i = 1; i <= iv->channels; i++) {
if (mPayload[iv->id].sts[i] == 3) {
uint8_t pos = iv->getPosByChFld(i, FLD_PDC, rec);
ac_pow += iv->getValue(pos, rec);
}
}
ac_pow = (int) (ac_pow*9.5);
iv->setValue(iv->getPosByChFld(0, FLD_PAC, rec), rec, (float) ac_pow/10);
int8_t rssi = -127;
for (uint8_t i = 0; i < 4; i++) {
// get best RSSI
if(mPayload[iv->id].rssi[i] > rssi)
rssi = mPayload[iv->id].rssi[i];
yield();
}
iv->rssi = rssi;
iv->doCalculations();
// update status state-machine,
iv->isProducing();
iv->setQueuedCmdFinished();
iv->radioStatistics.rxSuccess++;
yield();
notify(RealTimeRunData_Debug, iv);
}
bool build(Inverter<> *iv, bool *complete, bool *fastNext ) {
DPRINTLN(DBG_VERBOSE, F("build"));
// check if all messages are there
*complete = mPayload[iv->id].complete;
*fastNext = false;
uint8_t txCmd = mPayload[iv->id].txCmd;
if(!*complete) {
DPRINTLN(DBG_VERBOSE, F("incomlete, txCmd is 0x") + String(txCmd, HEX));
//we got some delayed status msgs?!?
if ((txCmd == MI_REQ_CH1) || (txCmd == MI_REQ_CH2)) {
if (mPayload[iv->id].stsAB[CH0] && mPayload[iv->id].dataAB[CH0]) {
miComplete(iv);
return true;
}
return false;
}
if (txCmd >= MI_REQ_4CH && txCmd <= 0x39) {
return false;
}
if (txCmd == 0x0f) { //hw info request, at least hw part nr. and version have to be there...
bool gotRelevant = iv->getFwVersion()
&& iv->getChannelFieldValue(CH0, FLD_PART_NUM, iv->getRecordStruct(InverterDevInform_Simple));
if (gotRelevant)
*fastNext = true;
return gotRelevant;
}
}
//check if we want the next request to be executed faster
if (mPayload[iv->id].gotFragment && txCmd == 0x0f)
*fastNext = true;
return true;
}
void miHwDecode(Inverter<> *iv, packet_t *p ) {
record_t<> *rec = iv->getRecordStruct(InverterDevInform_All); // choose the record structure
rec->ts = mPayload[iv->id].ts;
mPayload[iv->id].gotFragment = true;
/*
Polling the device software and hardware version number command
start byte Command word routing address target address User data check end byte
byte[0] byte[1] byte[2] byte[3] byte[4] byte[5] byte[6] byte[7] byte[8] byte[9] byte[10] byte[11] byte[12]
0x7e 0x0f xx xx xx xx YY YY YY YY 0x00 CRC 0x7f
Command Receipt - First Frame
start byte Command word target address routing address Multi-frame marking User data User data User data User data User data User data User data User data User data User data User data User data User data User data User data User data check end byte
byte[0] byte[1] byte[2] byte[3] byte[4] byte[5] byte[6] byte[7] byte[8] byte[9] byte[10] byte[11] byte[12] byte[13] byte[14] byte[15] byte[16] byte[17] byte[18] byte[19] byte[20] byte[21] byte[22] byte[23] byte[24] byte[25] byte[26] byte[27] byte[28]
0x7e 0x8f YY YY YY YY xx xx xx xx 0x00 USFWBuild_VER APPFWBuild_VER APPFWBuild_YYYY APPFWBuild_MMDD APPFWBuild_HHMM APPFW_PN HW_VER CRC 0x7f
Command Receipt - Second Frame
start byte Command word target address routing address Multi-frame marking User data User data User data User data User data User data User data User data User data User data User data User data User data User data User data User data check end byte
byte[0] byte[1] byte[2] byte[3] byte[4] byte[5] byte[6] byte[7] byte[8] byte[9] byte[10] byte[11] byte[12] byte[13] byte[14] byte[15] byte[16] byte[17] byte[18] byte[19] byte[20] byte[21] byte[22] byte[23] byte[24] byte[25] byte[26] byte[27] byte[28]
0x7e 0x8f YY YY YY YY xx xx xx xx 0x01 HW_PN HW_FB_TLmValue HW_FB_ReSPRT HW_GridSamp_ResValule HW_ECapValue Matching_APPFW_PN CRC 0x7f
Command receipt - third frame
start byte Command word target address routing address Multi-frame marking User data User data User data User data User data User data User data User data check end byte
byte[0] byte[1] byte[2] byte[3] byte[4] byte[5] byte[6] byte[7] byte[8] byte[9] byte[10] byte[11] byte[12] byte[13] byte[14] byte[15] byte[16] byte[15] byte[16] byte[17] byte[18]
0x7e 0x8f YY YY YY YY xx xx xx xx 0x12 APPFW_MINVER HWInfoAddr PNInfoCRC_gusv PNInfoCRC_gusv CRC 0x7f
*/
/*
case InverterDevInform_All:
rec->length = (uint8_t)(HMINFO_LIST_LEN);
rec->assign = (byteAssign_t *)InfoAssignment;
rec->pyldLen = HMINFO_PAYLOAD_LEN;
break;
const byteAssign_t InfoAssignment[] = {
{ FLD_FW_VERSION, UNIT_NONE, CH0, 0, 2, 1 },
{ FLD_FW_BUILD_YEAR, UNIT_NONE, CH0, 2, 2, 1 },
{ FLD_FW_BUILD_MONTH_DAY, UNIT_NONE, CH0, 4, 2, 1 },
{ FLD_FW_BUILD_HOUR_MINUTE, UNIT_NONE, CH0, 6, 2, 1 },
{ FLD_BOOTLOADER_VER, UNIT_NONE, CH0, 8, 2, 1 }
};
*/
if ( p->packet[9] == 0x00 ) {//first frame
//FLD_FW_VERSION
for (uint8_t i = 0; i < 5; i++) {
iv->setValue(i, rec, (float) ((p->packet[(12+2*i)] << 8) + p->packet[(13+2*i)])/1);
}
iv->isConnected = true;
if(mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id);
DPRINT(DBG_INFO,F("HW_VER is "));
DBGPRINTLN(String((p->packet[24] << 8) + p->packet[25]));
}
record_t<> *rec = iv->getRecordStruct(InverterDevInform_Simple); // choose the record structure
rec->ts = mPayload[iv->id].ts;
iv->setValue(1, rec, (uint32_t) ((p->packet[24] << 8) + p->packet[25])/1);
mPayload[iv->id].multi_parts +=4;
} 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);
if ( p->packet[9] == 0x01 ) {
DBGPRINTLN(F("got 2nd frame (hw info)"));
/* according to xlsx (different start byte -1!)
byte[11] to byte[14] HW_PN
byte[15] byte[16] HW_FB_TLmValue
byte[17] byte[18] HW_FB_ReSPRT
byte[19] byte[20] HW_GridSamp_ResValule
byte[21] byte[22] HW_ECapValue
byte[23] to byte[26] Matching_APPFW_PN*/
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]));
record_t<> *rec = iv->getRecordStruct(InverterDevInform_Simple); // choose the record structure
rec->ts = mPayload[iv->id].ts;
iv->setValue(0, rec, (uint32_t) ((((p->packet[10] << 8) | p->packet[11]) << 8 | p->packet[12]) << 8 | p->packet[13])/1);
if(mSerialDebug) {
DPRINT(DBG_INFO,F("HW_FB_TLmValue "));
DBGPRINTLN(String((p->packet[14] << 8) + p->packet[15]));
DPRINT(DBG_INFO,F("HW_FB_ReSPRT "));
DBGPRINTLN(String((p->packet[16] << 8) + p->packet[17]));
DPRINT(DBG_INFO,F("HW_GridSamp_ResValule "));
DBGPRINTLN(String((p->packet[18] << 8) + p->packet[19]));
DPRINT(DBG_INFO,F("HW_ECapValue "));
DBGPRINTLN(String((p->packet[20] << 8) + p->packet[21]));
DPRINT(DBG_INFO,F("Matching_APPFW_PN "));
DBGPRINTLN(String((uint32_t) (((p->packet[22] << 8) | p->packet[23]) << 8 | p->packet[24]) << 8 | p->packet[25]));
}
//notify(InverterDevInform_Simple, iv);
mPayload[iv->id].multi_parts +=2;
notify(InverterDevInform_All, iv);
} else {
DBGPRINTLN(F("3rd gen. inverter!"));
}
} else if ( p->packet[9] == 0x12 ) {//3rd frame
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINTLN(F("got 3rd frame (hw info)"));
/* according to xlsx (different start byte -1!)
byte[11] byte[12] APPFW_MINVER
byte[13] byte[14] HWInfoAddr
byte[15] byte[16] PNInfoCRC_gusv
byte[15] byte[16] PNInfoCRC_gusv (this really is double mentionned in xlsx...)
*/
if(mSerialDebug) {
DPRINT(DBG_INFO,F("APPFW_MINVER "));
DBGPRINTLN(String((p->packet[10] << 8) + p->packet[11]));
DPRINT(DBG_INFO,F("HWInfoAddr "));
DBGPRINTLN(String((p->packet[12] << 8) + p->packet[13]));
DPRINT(DBG_INFO,F("PNInfoCRC_gusv "));
DBGPRINTLN(String((p->packet[14] << 8) + p->packet[15]));
}
mPayload[iv->id].multi_parts++;
}
if (mPayload[iv->id].multi_parts > 5) {
iv->setQueuedCmdFinished();
mPayload[iv->id].complete = true;
mPayload[iv->id].rxTmo = true;
mPayload[iv->id].requested= false;
iv->radioStatistics.rxSuccess++;
}
if (mHighPrioIv == NULL)
mHighPrioIv = iv;
}
void miGPFDecode(Inverter<> *iv, packet_t *p ) {
mPayload[iv->id].gotFragment = true;
mPayload[iv->id].gotGPF = true;
record_t<> *rec = iv->getRecordStruct(InverterDevInform_Simple); // choose the record structure
rec->ts = mPayload[iv->id].ts;
iv->setValue(2, rec, (uint32_t) (((p->packet[10] << 8) | p->packet[11]))); //FLD_GRID_PROFILE_CODE
iv->setValue(3, rec, (uint32_t) (((p->packet[12] << 8) | p->packet[13]))); //FLD_GRID_PROFILE_VERSION
iv->setQueuedCmdFinished();
iv->radioStatistics.rxSuccess++;
/* according to xlsx (different start byte -1!)
Polling Grid-connected Protection Parameter File Command - Receipt
byte[10] ST1 indicates the status of the grid-connected protection file. ST1=1 indicates the default grid-connected protection file, ST=2 indicates that the grid-connected protection file is configured and normal, ST=3 indicates that the grid-connected protection file cannot be recognized, ST=4 indicates that the grid-connected protection file is damaged
byte[11] byte[12] CountryStd variable indicates the national standard code of the grid-connected protection file
byte[13] byte[14] Version indicates the version of the grid-connected protection file
byte[15] byte[16]
*/
if(mSerialDebug) {
DPRINT(DBG_INFO,F("ST1 "));
DBGPRINTLN(String(p->packet[9]));
DPRINT(DBG_INFO,F("CountryStd "));
DBGPRINTLN(String((p->packet[10] << 8) + p->packet[11]));
DPRINT(DBG_INFO,F("Version "));
DBGPRINTLN(String((p->packet[12] << 8) + p->packet[13]));
}
if (mHighPrioIv == NULL)
mHighPrioIv = iv;
}
void reset(uint8_t id, bool setTxTmo = true, bool clrSts = false) {
memset(mPayload[id].len, 0, MAX_PAYLOAD_ENTRIES);
mPayload[id].gotFragment = false;
mPayload[id].rxTmo = setTxTmo;// design: don't start with complete retransmit
mPayload[id].rtrRes = 0;
mPayload[id].multi_parts = 0;
mPayload[id].retransmits = 0;
mPayload[id].complete = false;
mPayload[id].dataAB[CH0] = true; //required for 1CH and 2CH devices
mPayload[id].dataAB[CH1] = true; //required for 1CH and 2CH devices
mPayload[id].dataAB[CH2] = true; //only required for 2CH devices
mPayload[id].stsAB[CH0] = true; //required for 1CH and 2CH devices
mPayload[id].stsAB[CH1] = true; //required for 1CH and 2CH devices
mPayload[id].stsAB[CH2] = true; //only required for 2CH devices
mPayload[id].txCmd = 0;
mPayload[id].requested = false;
mPayload[id].ts = *mTimestamp;
if (clrSts) { // only clear channel states at startup
mPayload[id].sts[0] = 0;
mPayload[id].sts[CH1] = 0;
mPayload[id].sts[CH2] = 0;
mPayload[id].sts[CH3] = 0;
mPayload[id].sts[CH4] = 0;
}
}
IApp *mApp;
HMSYSTEM *mSys;
uint8_t mMaxRetrans;
uint32_t *mTimestamp;
miPayload_t mPayload[MAX_NUM_INVERTERS];
bool mSerialDebug;
Inverter<> *mHighPrioIv;
alarmListenerType mCbAlarm;
payloadListenerType mCbPayload;
};
#endif /*__MI_PAYLOAD_H__*/

11
src/web/RestApi.h

@ -680,12 +680,10 @@ class RestApi {
iv->powerLimit[1] = AbsolutNonPersistent;
accepted = iv->setDevControlRequest(ActivePowerContr);
}
else if(F("dev") == jsonIn[F("cmd")]) {
} else if(F("dev") == jsonIn[F("cmd")]) {
DPRINTLN(DBG_INFO, F("dev cmd"));
//iv->enqueCommand<InfoCommand>(jsonIn[F("val")].as<int>());
}
else {
iv->setDevCommand(jsonIn[F("val")].as<int>());
} else {
jsonOut[F("error")] = F("unknown cmd: '") + jsonIn["cmd"].as<String>() + "'";
return false;
}
@ -693,8 +691,7 @@ class RestApi {
if(!accepted) {
jsonOut[F("error")] = F("inverter does not accept dev control request at this moment");
return false;
} else
mApp->ivSendHighPrio(iv);
}
return true;
}

Loading…
Cancel
Save