mirror of
https://github.com/lumapu/ahoy.git
synced 2025-06-15 00:51:38 +02:00
improved HMS implementation, RX not functional
Tx visible on SDR @ 863MHz
This commit is contained in:
parent
5525d25e4b
commit
3a25ebb26f
11 changed files with 616 additions and 131 deletions
31
src/app.cpp
31
src/app.cpp
|
@ -42,7 +42,7 @@ void app::setup() {
|
|||
}
|
||||
#if defined(ESP32)
|
||||
if(mConfig->cmt.enabled) {
|
||||
mCmtRadio.setup();
|
||||
mCmtRadio.setup(mConfig->cmt.pinCsb, mConfig->cmt.pinFcsb, false);
|
||||
mCmtRadio.enableDebug();
|
||||
}
|
||||
#endif
|
||||
|
@ -66,6 +66,13 @@ void app::setup() {
|
|||
|
||||
mMiPayload.setup(this, &mSys, &mNrfRadio, &mStat, mConfig->nrf.maxRetransPerPyld, &mTimestamp);
|
||||
mMiPayload.enableSerialDebug(mConfig->serial.debug);
|
||||
|
||||
if(!mNrfRadio.isChipConnected())
|
||||
DPRINTLN(DBG_WARN, F("WARNING! your NRF24 module can't be reached, check the wiring"));
|
||||
}
|
||||
if(mConfig->cmt.enabled) {
|
||||
mHmsPayload.setup(this, &mSys, &mCmtRadio, &mStat, 5, &mTimestamp);
|
||||
mHmsPayload.enableSerialDebug(mConfig->serial.debug);
|
||||
}
|
||||
|
||||
/*DBGPRINTLN("--- after payload");
|
||||
|
@ -73,8 +80,6 @@ void app::setup() {
|
|||
DBGPRINTLN(String(ESP.getHeapFragmentation()));
|
||||
DBGPRINTLN(String(ESP.getMaxFreeBlockSize()));*/
|
||||
|
||||
if(!mNrfRadio.isChipConnected() && mConfig->nrf.enabled)
|
||||
DPRINTLN(DBG_WARN, F("WARNING! your NRF24 module can't be reached, check the wiring"));
|
||||
|
||||
// when WiFi is in client mode, then enable mqtt broker
|
||||
#if !defined(AP_ONLY)
|
||||
|
@ -182,7 +187,7 @@ void app::onWifi(bool gotIp) {
|
|||
every(std::bind(&app::tickSend, this), mConfig->nrf.sendInterval, "tSend");
|
||||
#if defined(ESP32)
|
||||
if(mConfig->cmt.enabled)
|
||||
everySec(std::bind(&CmtRadioType::tickSecond, mCmtRadio), "tsCmt");
|
||||
everySec(std::bind(&CmtRadioType::tickSecond, &mCmtRadio), "tsCmt");
|
||||
#endif
|
||||
mMqttReconnect = true;
|
||||
mSunrise = 0; // needs to be set to 0, to reinstall sunrise and ivComm tickers!
|
||||
|
@ -355,10 +360,10 @@ void app::tickMidnight(void) {
|
|||
|
||||
//-----------------------------------------------------------------------------
|
||||
void app::tickSend(void) {
|
||||
if(!mNrfRadio.isChipConnected()) {
|
||||
/*if(!mNrfRadio.isChipConnected()) {
|
||||
DPRINTLN(DBG_WARN, F("NRF24 not connected!"));
|
||||
return;
|
||||
}
|
||||
}*/
|
||||
if (mIVCommunicationOn) {
|
||||
if (!mNrfRadio.mBufCtrl.empty()) {
|
||||
if (mConfig->serial.debug) {
|
||||
|
@ -366,6 +371,14 @@ void app::tickSend(void) {
|
|||
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);
|
||||
|
@ -378,8 +391,12 @@ void app::tickSend(void) {
|
|||
if(iv->config->enabled) {
|
||||
if(iv->ivGen == IV_HM)
|
||||
mPayload.ivSend(iv);
|
||||
else
|
||||
else if(iv->ivGen == IV_MI)
|
||||
mMiPayload.ivSend(iv);
|
||||
#if defined(ESP32)
|
||||
else if(iv->ivGen == IV_HMS)
|
||||
mHmsPayload.ivSend(iv);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
} else {
|
||||
|
|
11
src/app.h
11
src/app.h
|
@ -21,6 +21,7 @@
|
|||
#include "hm/hmSystem.h"
|
||||
#include "hm/hmRadio.h"
|
||||
#include "hms/hmsRadio.h"
|
||||
#include "hms/hmsPayload.h"
|
||||
#include "hm/hmPayload.h"
|
||||
#include "hm/miPayload.h"
|
||||
#include "wifi/ahoywifi.h"
|
||||
|
@ -41,6 +42,7 @@ typedef CmtRadio<esp32_3wSpi<>> CmtRadioType;
|
|||
typedef HmSystem<MAX_NUM_INVERTERS> HmSystemType;
|
||||
typedef HmPayload<HmSystemType, HmRadio<>> PayloadType;
|
||||
typedef MiPayload<HmSystemType, HmRadio<>> MiPayloadType;
|
||||
typedef HmsPayload<HmSystemType, CmtRadioType> HmsPayloadType;
|
||||
typedef Web<HmSystemType> WebType;
|
||||
typedef RestApi<HmSystemType, HmRadio<>> RestApiType;
|
||||
typedef PubMqtt<HmSystemType> PubMqttType;
|
||||
|
@ -212,10 +214,6 @@ class app : public IApp, public ah::Scheduler {
|
|||
Scheduler::setTimestamp(newTime);
|
||||
}
|
||||
|
||||
HmSystemType mSys;
|
||||
HmRadio<> mNrfRadio;
|
||||
CmtRadioType mCmtRadio;
|
||||
|
||||
private:
|
||||
typedef std::function<void()> innerLoopCb;
|
||||
|
||||
|
@ -269,6 +267,10 @@ class app : public IApp, public ah::Scheduler {
|
|||
|
||||
innerLoopCb mInnerLoopCb;
|
||||
|
||||
HmSystemType mSys;
|
||||
HmRadio<> mNrfRadio;
|
||||
CmtRadioType mCmtRadio;
|
||||
|
||||
bool mShowRebootRequest;
|
||||
bool mIVCommunicationOn;
|
||||
|
||||
|
@ -277,6 +279,7 @@ class app : public IApp, public ah::Scheduler {
|
|||
RestApiType mApi;
|
||||
PayloadType mPayload;
|
||||
MiPayloadType mMiPayload;
|
||||
HmsPayloadType mHmsPayload;
|
||||
PubSerialType mPubSerial;
|
||||
|
||||
char mVersion[12];
|
||||
|
|
|
@ -23,27 +23,6 @@
|
|||
const char* const rf24AmpPowerNames[] = {"MIN", "LOW", "HIGH", "MAX"};
|
||||
|
||||
|
||||
//-----------------------------------------------------------------------------
|
||||
// MACROS
|
||||
//-----------------------------------------------------------------------------
|
||||
#define CP_U32_LittleEndian(buf, v) ({ \
|
||||
uint8_t *b = buf; \
|
||||
b[0] = ((v >> 24) & 0xff); \
|
||||
b[1] = ((v >> 16) & 0xff); \
|
||||
b[2] = ((v >> 8) & 0xff); \
|
||||
b[3] = ((v ) & 0xff); \
|
||||
})
|
||||
|
||||
#define CP_U32_BigEndian(buf, v) ({ \
|
||||
uint8_t *b = buf; \
|
||||
b[3] = ((v >> 24) & 0xff); \
|
||||
b[2] = ((v >> 16) & 0xff); \
|
||||
b[1] = ((v >> 8) & 0xff); \
|
||||
b[0] = ((v ) & 0xff); \
|
||||
})
|
||||
|
||||
#define BIT_CNT(x) ((x)<<3)
|
||||
|
||||
//-----------------------------------------------------------------------------
|
||||
// HM Radio class
|
||||
//-----------------------------------------------------------------------------
|
||||
|
|
|
@ -172,9 +172,14 @@ class Cmt2300a {
|
|||
public:
|
||||
Cmt2300a() {}
|
||||
|
||||
void setup(uint8_t pinCsb, uint8_t pinFcsb) {
|
||||
mSpi.setup(pinCsb, pinFcsb);
|
||||
init();
|
||||
}
|
||||
|
||||
void setup() {
|
||||
mSpi.setup();
|
||||
mTxPending = false;
|
||||
init();
|
||||
}
|
||||
|
||||
// call as often as possible
|
||||
|
@ -189,23 +194,13 @@ class Cmt2300a {
|
|||
}
|
||||
}
|
||||
|
||||
inline void swichChannel(bool reset = true, uint8_t start = 0x00, uint8_t end = 0x22) {
|
||||
if(reset)
|
||||
mRxTxCh = start;
|
||||
else if(++mRxTxCh > end)
|
||||
mRxTxCh = start;
|
||||
// 0: 868.00MHz
|
||||
// 1: 868.23MHz
|
||||
// 2: 868.46MHz
|
||||
// 3: 868.72MHz
|
||||
// 4: 868.97MHz
|
||||
mSpi.writeReg(CMT2300A_CUS_FREQ_CHNL, mRxTxCh);
|
||||
}
|
||||
|
||||
uint8_t goRx(void) {
|
||||
if(mTxPending)
|
||||
return CMT_ERR_TX_PENDING;
|
||||
|
||||
if(mInRxMode)
|
||||
return CMT_SUCCESS;
|
||||
|
||||
mSpi.readReg(CMT2300A_CUS_INT1_CTL);
|
||||
mSpi.writeReg(CMT2300A_CUS_INT1_CTL, CMT2300A_INT_SEL_TX_DONE);
|
||||
|
||||
|
@ -229,10 +224,16 @@ class Cmt2300a {
|
|||
|
||||
mSpi.writeReg(CMT2300A_CUS_FREQ_CHNL, 0x00); // 863.0 MHz
|
||||
|
||||
if(!cmtSwitchStatus(CMT2300A_GO_RX, CMT2300A_STA_RX))
|
||||
if(!cmtSwitchStatus(CMT2300A_GO_RX, CMT2300A_STA_RX)) {
|
||||
Serial.println("Go RX");
|
||||
return CMT_ERR_SWITCH_STATE;
|
||||
}
|
||||
|
||||
mInRxMode = true;
|
||||
|
||||
return CMT_SUCCESS;
|
||||
}
|
||||
|
||||
uint8_t checkRx(uint8_t buf[], uint8_t len, int8_t *rssi) {
|
||||
if(mTxPending)
|
||||
return CMT_ERR_TX_PENDING;
|
||||
|
@ -253,16 +254,26 @@ class Cmt2300a {
|
|||
if(!cmtSwitchStatus(CMT2300A_GO_STBY, CMT2300A_STA_STBY))
|
||||
return CMT_ERR_SWITCH_STATE;
|
||||
|
||||
mInRxMode = false;
|
||||
mCusIntFlag = mSpi.readReg(CMT2300A_CUS_INT_FLAG);
|
||||
|
||||
return CMT_SUCCESS;
|
||||
}
|
||||
|
||||
bool tx(uint8_t buf[], uint8_t len) {
|
||||
uint8_t tx(uint8_t buf[], uint8_t len) {
|
||||
if(mTxPending)
|
||||
return CMT_ERR_TX_PENDING;
|
||||
|
||||
if(mInRxMode) {
|
||||
mInRxMode = false;
|
||||
if(!cmtSwitchStatus(CMT2300A_GO_STBY, CMT2300A_STA_STBY))
|
||||
return CMT_ERR_SWITCH_STATE;
|
||||
}
|
||||
|
||||
mSpi.writeReg(CMT2300A_CUS_INT1_CTL, CMT2300A_INT_SEL_TX_DONE);
|
||||
|
||||
if(0x00 == mSpi.readReg(CMT2300A_CUS_INT_FLAG)) {
|
||||
//mCusIntFlag == mSpi.readReg(CMT2300A_CUS_INT_FLAG);
|
||||
//if(0x00 == mCusIntFlag) {
|
||||
// no data received
|
||||
mSpi.readReg(CMT2300A_CUS_INT_CLR1);
|
||||
mSpi.writeReg(CMT2300A_CUS_INT_CLR1, 0x00);
|
||||
|
@ -278,16 +289,16 @@ class Cmt2300a {
|
|||
mSpi.writeFifo(buf, len);
|
||||
|
||||
// send only on base frequency: here 863.0 MHz
|
||||
mSpi.writeReg(CMT2300A_CUS_FREQ_CHNL, 0x00);
|
||||
swichChannel((len != 15));
|
||||
|
||||
if(!cmtSwitchStatus(CMT2300A_GO_TX, CMT2300A_STA_TX))
|
||||
return CMT_ERR_SWITCH_STATE;
|
||||
|
||||
// wait for tx done
|
||||
mTxPending = CMT_SUCCESS;
|
||||
}
|
||||
else
|
||||
return CMT_ERR_RX_IN_FIFO;
|
||||
mTxPending = true;
|
||||
//}
|
||||
//else
|
||||
// return CMT_ERR_RX_IN_FIFO;
|
||||
|
||||
return CMT_SUCCESS;
|
||||
}
|
||||
|
@ -297,7 +308,7 @@ class Cmt2300a {
|
|||
mSpi.writeReg(0x7f, 0xff); // soft reset
|
||||
delay(30);
|
||||
|
||||
if(cmtSwitchStatus(CMT2300A_GO_STBY, CMT2300A_STA_STBY))
|
||||
if(!cmtSwitchStatus(CMT2300A_GO_STBY, CMT2300A_STA_STBY))
|
||||
return false;
|
||||
|
||||
if(0xAA != mSpi.readReg(0x48))
|
||||
|
@ -384,6 +395,13 @@ class Cmt2300a {
|
|||
}
|
||||
|
||||
private:
|
||||
void init() {
|
||||
mTxPending = false;
|
||||
mInRxMode = false;
|
||||
mCusIntFlag = 0x00;
|
||||
mCnt = 0;
|
||||
}
|
||||
|
||||
// CMT state machine, wait for next state, true on success
|
||||
bool cmtSwitchStatus(uint8_t cmd, uint8_t waitFor, uint16_t cycles = 40) {
|
||||
mSpi.writeReg(CMT2300A_CUS_MODE_CTL, cmd);
|
||||
|
@ -397,13 +415,35 @@ class Cmt2300a {
|
|||
return false;
|
||||
}
|
||||
|
||||
inline void swichChannel(bool def = true, uint8_t start = 0x00, uint8_t end = 0x22) {
|
||||
if(!def) {
|
||||
if(++mCnt > 2) {
|
||||
if(++mRxTxCh > end)
|
||||
mRxTxCh = start;
|
||||
mCnt = 0;
|
||||
}
|
||||
}
|
||||
// 0: 868.00MHz
|
||||
// 1: 868.23MHz
|
||||
// 2: 868.46MHz
|
||||
// 3: 868.72MHz
|
||||
// 4: 868.97MHz
|
||||
if(!def)
|
||||
mSpi.writeReg(CMT2300A_CUS_FREQ_CHNL, mRxTxCh);
|
||||
else
|
||||
mSpi.writeReg(CMT2300A_CUS_FREQ_CHNL, 0x00);
|
||||
}
|
||||
|
||||
inline uint8_t getChipStatus(void) {
|
||||
return mSpi.readReg(CMT2300A_CUS_MODE_STA) & CMT2300A_MASK_CHIP_MODE_STA;
|
||||
}
|
||||
|
||||
SpiType mSpi;
|
||||
uint8_t mCnt;
|
||||
bool mTxPending;
|
||||
uint8_t mRxTxCh;
|
||||
bool mInRxMode;
|
||||
uint8_t mCusIntFlag;
|
||||
};
|
||||
|
||||
#endif /*__CMT2300A_H__*/
|
||||
|
|
|
@ -17,11 +17,14 @@
|
|||
|
||||
#define SPI_CLK 1 * 1000 * 1000 // 1MHz
|
||||
|
||||
template<uint8_t CSB_PIN=5, uint8_t FCSB_PIN=4, uint8_t GPIO3_PIN=15>
|
||||
template<uint8_t CSB_PIN=5, uint8_t FCSB_PIN=4> //, uint8_t GPIO3_PIN=15>
|
||||
class esp32_3wSpi {
|
||||
public:
|
||||
esp32_3wSpi() {}
|
||||
void setup() {
|
||||
esp32_3wSpi() {
|
||||
mInitialized = false;
|
||||
}
|
||||
|
||||
void setup(uint8_t pinCsb = CSB_PIN, uint8_t pinFcsb = FCSB_PIN) { //, uint8_t pinGpio3 = GPIO3_PIN) {
|
||||
spi_bus_config_t buscfg = {
|
||||
.mosi_io_num = MOSI_PIN,
|
||||
.miso_io_num = MISO_PIN,
|
||||
|
@ -35,8 +38,8 @@ class esp32_3wSpi {
|
|||
.address_bits = 0,
|
||||
.dummy_bits = 0,
|
||||
.mode = 0, // SPI mode 0
|
||||
.clock_speed_hz = SPI_CLK, // 1 MHz
|
||||
.spics_io_num = CSB_PIN,
|
||||
.clock_speed_hz = SPI_CLK,
|
||||
.spics_io_num = pinCsb,
|
||||
.flags = SPI_DEVICE_HALFDUPLEX | SPI_DEVICE_3WIRE,
|
||||
.queue_size = 1,
|
||||
.pre_cb = NULL,
|
||||
|
@ -54,8 +57,8 @@ class esp32_3wSpi {
|
|||
.mode = 0, // SPI mode 0
|
||||
.cs_ena_pretrans = 2,
|
||||
.cs_ena_posttrans = (uint8_t)(1 / (SPI_CLK * 10e6 * 2) + 2), // >2 us
|
||||
.clock_speed_hz = SPI_CLK, // 1 MHz
|
||||
.spics_io_num = FCSB_PIN,
|
||||
.clock_speed_hz = SPI_CLK,
|
||||
.spics_io_num = pinFcsb,
|
||||
.flags = SPI_DEVICE_HALFDUPLEX | SPI_DEVICE_3WIRE,
|
||||
.queue_size = 1,
|
||||
.pre_cb = NULL,
|
||||
|
@ -66,10 +69,14 @@ class esp32_3wSpi {
|
|||
esp_rom_gpio_connect_out_signal(MOSI_PIN, spi_periph_signal[SPI2_HOST].spid_out, true, false);
|
||||
delay(100);
|
||||
|
||||
pinMode(GPIO3_PIN, INPUT);
|
||||
//pinMode(pinGpio3, INPUT);
|
||||
mInitialized = true;
|
||||
}
|
||||
|
||||
void writeReg(uint8_t addr, uint8_t reg) {
|
||||
if(!mInitialized)
|
||||
return;
|
||||
|
||||
uint8_t tx_data[2];
|
||||
tx_data[0] = ~addr;
|
||||
tx_data[1] = ~reg;
|
||||
|
@ -83,6 +90,9 @@ class esp32_3wSpi {
|
|||
}
|
||||
|
||||
uint8_t readReg(uint8_t addr) {
|
||||
if(!mInitialized)
|
||||
return 0;
|
||||
|
||||
uint8_t tx_data, rx_data;
|
||||
tx_data = ~(addr | 0x80); // negation and MSB high (read command)
|
||||
spi_transaction_t t = {
|
||||
|
@ -97,6 +107,8 @@ class esp32_3wSpi {
|
|||
}
|
||||
|
||||
void writeFifo(uint8_t buf[], uint8_t len) {
|
||||
if(!mInitialized)
|
||||
return;
|
||||
uint8_t tx_data;
|
||||
|
||||
spi_transaction_t t = {
|
||||
|
@ -114,6 +126,8 @@ class esp32_3wSpi {
|
|||
}
|
||||
|
||||
void readFifo(uint8_t buf[], uint8_t len) {
|
||||
if(!mInitialized)
|
||||
return;
|
||||
uint8_t rx_data;
|
||||
|
||||
spi_transaction_t t = {
|
||||
|
@ -132,6 +146,7 @@ class esp32_3wSpi {
|
|||
|
||||
private:
|
||||
spi_device_handle_t spi_reg, spi_fifo;
|
||||
bool mInitialized;
|
||||
};
|
||||
#endif
|
||||
|
||||
|
|
405
src/hms/hmsPayload.h
Normal file
405
src/hms/hmsPayload.h
Normal file
|
@ -0,0 +1,405 @@
|
|||
//-----------------------------------------------------------------------------
|
||||
// 2023 Ahoy, https://ahoydtu.de
|
||||
// Creative Commons - http://creativecommons.org/licenses/by-nc-sa/3.0/de/
|
||||
//-----------------------------------------------------------------------------
|
||||
|
||||
#ifndef __HMS_PAYLOAD_H__
|
||||
#define __HMS_PAYLOAD_H__
|
||||
|
||||
#include "../utils/dbg.h"
|
||||
#include "../utils/crc.h"
|
||||
#include "../config/config.h"
|
||||
#include <Arduino.h>
|
||||
|
||||
typedef struct {
|
||||
//uint8_t txCmd;
|
||||
//uint8_t txId;
|
||||
//uint8_t invId;
|
||||
uint32_t ts;
|
||||
//uint8_t data[MAX_PAYLOAD_ENTRIES][MAX_RF_PAYLOAD_SIZE];
|
||||
uint8_t len[MAX_PAYLOAD_ENTRIES];
|
||||
//bool complete;
|
||||
//uint8_t maxPackId;
|
||||
//bool lastFound;
|
||||
//uint8_t retransmits;
|
||||
bool requested;
|
||||
//bool gotFragment;
|
||||
} hmsPayload_t;
|
||||
|
||||
|
||||
typedef std::function<void(uint8_t)> payloadListenerType;
|
||||
typedef std::function<void(uint16_t alarmCode, uint32_t start, uint32_t end)> alarmListenerType;
|
||||
|
||||
|
||||
template<class HMSYSTEM, class RADIO>
|
||||
class HmsPayload {
|
||||
public:
|
||||
HmsPayload() {}
|
||||
|
||||
void setup(IApp *app, HMSYSTEM *sys, RADIO *radio, statistics_t *stat, uint8_t maxRetransmits, uint32_t *timestamp) {
|
||||
mApp = app;
|
||||
mSys = sys;
|
||||
mRadio = radio;
|
||||
mStat = stat;
|
||||
mMaxRetrans = maxRetransmits;
|
||||
mTimestamp = timestamp;
|
||||
for(uint8_t i = 0; i < MAX_NUM_INVERTERS; i++) {
|
||||
reset(i);
|
||||
}
|
||||
mSerialDebug = false;
|
||||
//mHighPrioIv = NULL;
|
||||
mCbAlarm = NULL;
|
||||
mCbPayload = NULL;
|
||||
mFirst = true;
|
||||
}
|
||||
|
||||
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);
|
||||
mHighPrioIv = NULL;
|
||||
}*/
|
||||
}
|
||||
|
||||
void ivSendHighPrio(Inverter<> *iv) {
|
||||
//mHighPrioIv = iv;
|
||||
}
|
||||
|
||||
void ivSend(Inverter<> *iv, bool highPrio = false) {
|
||||
if(mFirst) {
|
||||
mFirst = false;
|
||||
mRadio->setIvBackChannel(&iv->radioId.u64);
|
||||
} else {
|
||||
reset(iv->id);
|
||||
mPayload[iv->id].requested = true;
|
||||
mRadio->prepareDevInformCmd(&iv->radioId.u64, 0x0b, mPayload[iv->id].ts, iv->alarmMesIndex, false);
|
||||
}
|
||||
/*if(!highPrio) {
|
||||
if (mPayload[iv->id].requested) {
|
||||
if (!mPayload[iv->id].complete)
|
||||
process(false); // no retransmit
|
||||
|
||||
if (!mPayload[iv->id].complete) {
|
||||
if (MAX_PAYLOAD_ENTRIES == mPayload[iv->id].maxPackId)
|
||||
mStat->rxFailNoAnser++; // got nothing
|
||||
else
|
||||
mStat->rxFail++; // got fragments but not complete response
|
||||
|
||||
iv->setQueuedCmdFinished(); // command failed
|
||||
if (mSerialDebug)
|
||||
DPRINTLN(DBG_INFO, F("enqueued cmd failed/timeout"));
|
||||
if (mSerialDebug) {
|
||||
DPRINT(DBG_INFO, F("(#"));
|
||||
DBGPRINT(String(iv->id));
|
||||
DBGPRINT(F(") no Payload received! (retransmits: "));
|
||||
DBGPRINT(String(mPayload[iv->id].retransmits));
|
||||
DBGPRINTLN(F(")"));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
reset(iv->id);
|
||||
mPayload[iv->id].requested = true;
|
||||
|
||||
yield();
|
||||
if (mSerialDebug) {
|
||||
DPRINT(DBG_INFO, F("(#"));
|
||||
DBGPRINT(String(iv->id));
|
||||
DBGPRINT(F(") Requesting Inv SN "));
|
||||
DBGPRINTLN(String(iv->config->serial.u64, HEX));
|
||||
}
|
||||
|
||||
if (iv->getDevControlRequest()) {
|
||||
if (mSerialDebug) {
|
||||
DPRINT(DBG_INFO, F("(#"));
|
||||
DBGPRINT(String(iv->id));
|
||||
DBGPRINT(F(") Devcontrol request 0x"));
|
||||
DBGPRINT(String(iv->devControlCmd, HEX));
|
||||
DBGPRINT(F(" power limit "));
|
||||
DBGPRINTLN(String(iv->powerLimit[0]));
|
||||
}
|
||||
mRadio->sendControlPacket(iv->radioId.u64, iv->devControlCmd, iv->powerLimit, false);
|
||||
mPayload[iv->id].txCmd = iv->devControlCmd;
|
||||
//iv->clearCmdQueue();
|
||||
//iv->enqueCommand<InfoCommand>(SystemConfigPara); // read back power limit
|
||||
} else {
|
||||
uint8_t cmd = iv->getQueuedCmd();
|
||||
DPRINT(DBG_INFO, F("(#"));
|
||||
DBGPRINT(String(iv->id));
|
||||
DBGPRINT(F(") prepareDevInformCmd")); // + String(cmd, HEX));
|
||||
mRadio->prepareDevInformCmd(iv->radioId.u64, cmd, mPayload[iv->id].ts, iv->alarmMesIndex, 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) {
|
||||
DPRINT(DBG_DEBUG, F("fragment number zero received and ignored"));
|
||||
} else {
|
||||
DPRINTLN(DBG_DEBUG, "PID: 0x" + 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;
|
||||
}
|
||||
|
||||
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);
|
||||
else
|
||||
ok = false;
|
||||
DPRINT(DBG_INFO, F("(#"));
|
||||
DBGPRINT(String(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 "));
|
||||
DBGPRINT(String(iv->powerLimit[1]));
|
||||
|
||||
iv->clearCmdQueue();
|
||||
iv->enqueCommand<InfoCommand>(SystemConfigPara); // read back power limit
|
||||
}
|
||||
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 (IV_MI == iv->ivGen) // only process HM inverters
|
||||
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 (!mPayload[iv->id].complete) {
|
||||
bool crcPass, pyldComplete;
|
||||
crcPass = build(iv->id, &pyldComplete);
|
||||
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) {
|
||||
DPRINTLN(DBG_INFO, F("retransmit power limit"));
|
||||
mRadio->sendControlPacket(iv->radioId.u64, iv->devControlCmd, iv->powerLimit, true);
|
||||
} else {
|
||||
if(false == mPayload[iv->id].gotFragment) {
|
||||
|
||||
//DPRINTLN(DBG_WARN, F("nothing received: Request Complete Retransmit"));
|
||||
//mPayload[iv->id].txCmd = iv->getQueuedCmd();
|
||||
//DPRINTLN(DBG_INFO, F("(#") + String(iv->id) + F(") prepareDevInformCmd 0x") + String(mPayload[iv->id].txCmd, HEX));
|
||||
//mRadio->prepareDevInformCmd(iv->radioId.u64, mPayload[iv->id].txCmd, mPayload[iv->id].ts, iv->alarmMesIndex, true);
|
||||
|
||||
DPRINT(DBG_INFO, F("(#"));
|
||||
DBGPRINT(String(iv->id));
|
||||
DBGPRINTLN(F(") nothing received"));
|
||||
mPayload[iv->id].retransmits = mMaxRetrans;
|
||||
} else {
|
||||
for (uint8_t i = 0; i < (mPayload[iv->id].maxPackId - 1); i++) {
|
||||
if (mPayload[iv->id].len[i] == 0) {
|
||||
DPRINT(DBG_WARN, F("Frame "));
|
||||
DBGPRINT(String(i + 1));
|
||||
DBGPRINTLN(F(" missing: Request Retransmit"));
|
||||
mRadio->sendCmdPacket(iv->radioId.u64, TX_REQ_INFO, (SINGLE_FRAME + i), true);
|
||||
break; // only request retransmit one frame per loop
|
||||
}
|
||||
yield();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
} else if(!crcPass && pyldComplete) { // crc error on complete Payload
|
||||
if (mPayload[iv->id].retransmits < mMaxRetrans) {
|
||||
mPayload[iv->id].retransmits++;
|
||||
DPRINTLN(DBG_WARN, F("CRC Error: Request Complete Retransmit"));
|
||||
mPayload[iv->id].txCmd = iv->getQueuedCmd();
|
||||
DPRINT(DBG_INFO, F("(#"));
|
||||
DBGPRINT(String(iv->id));
|
||||
DBGPRINT(F(") prepareDevInformCmd 0x"));
|
||||
DBGPRINTLN(String(mPayload[iv->id].txCmd, HEX));
|
||||
mRadio->prepareDevInformCmd(iv->radioId.u64, mPayload[iv->id].txCmd, mPayload[iv->id].ts, iv->alarmMesIndex, true);
|
||||
}
|
||||
} else { // payload complete
|
||||
DPRINT(DBG_INFO, F("procPyld: cmd: 0x"));
|
||||
DBGPRINTLN(String(mPayload[iv->id].txCmd, HEX));
|
||||
DPRINT(DBG_INFO, F("procPyld: txid: 0x"));
|
||||
DBGPRINTLN(String(mPayload[iv->id].txId, HEX));
|
||||
DPRINTLN(DBG_DEBUG, F("procPyld: max: ") + String(mPayload[iv->id].maxPackId));
|
||||
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);
|
||||
|
||||
for (uint8_t i = 0; i < (mPayload[iv->id].maxPackId); i++) {
|
||||
memcpy(&payload[payloadLen], mPayload[iv->id].data[i], (mPayload[iv->id].len[i]));
|
||||
payloadLen += (mPayload[iv->id].len[i]);
|
||||
yield();
|
||||
}
|
||||
payloadLen -= 2;
|
||||
|
||||
if (mSerialDebug) {
|
||||
DPRINT(DBG_INFO, 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))
|
||||
mStat->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);
|
||||
|
||||
if(AlarmData == mPayload[iv->id].txCmd) {
|
||||
uint8_t i = 0;
|
||||
uint16_t code;
|
||||
uint32_t start, end;
|
||||
while(1) {
|
||||
code = iv->parseAlarmLog(i++, payload, payloadLen, &start, &end);
|
||||
if(0 == code)
|
||||
break;
|
||||
if (NULL != mCbAlarm)
|
||||
(mCbAlarm)(code, start, end);
|
||||
yield();
|
||||
}
|
||||
}
|
||||
} else {
|
||||
DPRINT(DBG_ERROR, F("plausibility check failed, expected "));
|
||||
DBGPRINT(String(rec->pyldLen));
|
||||
DBGPRINTLN(F(" bytes"));
|
||||
mStat->rxFail++;
|
||||
}
|
||||
|
||||
iv->setQueuedCmdFinished();
|
||||
}
|
||||
}
|
||||
yield();
|
||||
}*/
|
||||
}
|
||||
|
||||
private:
|
||||
void notify(uint8_t val) {
|
||||
if(NULL != mCbPayload)
|
||||
(mCbPayload)(val);
|
||||
}
|
||||
|
||||
void notify(uint16_t code, uint32_t start, uint32_t endTime) {
|
||||
if (NULL != mCbAlarm)
|
||||
(mCbAlarm)(code, start, endTime);
|
||||
}
|
||||
|
||||
bool build(uint8_t id, bool *complete) {
|
||||
/*DPRINTLN(DBG_VERBOSE, F("build"));
|
||||
uint16_t crc = 0xffff, crcRcv = 0x0000;
|
||||
if (mPayload[id].maxPackId > MAX_PAYLOAD_ENTRIES)
|
||||
mPayload[id].maxPackId = MAX_PAYLOAD_ENTRIES;
|
||||
|
||||
// check if all fragments are there
|
||||
*complete = true;
|
||||
for (uint8_t i = 0; i < mPayload[id].maxPackId; i++) {
|
||||
if(mPayload[id].len[i] == 0)
|
||||
*complete = false;
|
||||
}
|
||||
if(!*complete)
|
||||
return false;
|
||||
|
||||
for (uint8_t i = 0; i < mPayload[id].maxPackId; i++) {
|
||||
if (mPayload[id].len[i] > 0) {
|
||||
if (i == (mPayload[id].maxPackId - 1)) {
|
||||
crc = ah::crc16(mPayload[id].data[i], mPayload[id].len[i] - 2, crc);
|
||||
crcRcv = (mPayload[id].data[i][mPayload[id].len[i] - 2] << 8) | (mPayload[id].data[i][mPayload[id].len[i] - 1]);
|
||||
} else
|
||||
crc = ah::crc16(mPayload[id].data[i], mPayload[id].len[i], crc);
|
||||
}
|
||||
yield();
|
||||
}
|
||||
|
||||
return (crc == crcRcv) ? true : false;*/
|
||||
return true;
|
||||
}
|
||||
|
||||
void reset(uint8_t id) {
|
||||
DPRINT(DBG_INFO, "resetPayload: id: ");
|
||||
DBGPRINTLN(String(id));
|
||||
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;
|
||||
}
|
||||
|
||||
IApp *mApp;
|
||||
HMSYSTEM *mSys;
|
||||
RADIO *mRadio;
|
||||
statistics_t *mStat;
|
||||
uint8_t mMaxRetrans;
|
||||
uint32_t *mTimestamp;
|
||||
hmsPayload_t mPayload[MAX_NUM_INVERTERS];
|
||||
bool mSerialDebug;
|
||||
Inverter<> *mHighPrioIv;
|
||||
bool mFirst;
|
||||
|
||||
alarmListenerType mCbAlarm;
|
||||
payloadListenerType mCbPayload;
|
||||
};
|
||||
|
||||
#endif /*__HMS_PAYLOAD_H__*/
|
|
@ -19,7 +19,7 @@ typedef struct {
|
|||
#define U32_B1(val) ((uint8_t)((val >> 8) & 0xff))
|
||||
#define U32_B0(val) ((uint8_t)((val ) & 0xff))
|
||||
|
||||
template<class SPI, uint32_t DTU_SN = 0x87654321>
|
||||
template<class SPI, uint32_t DTU_SN = 0x81001765>
|
||||
class CmtRadio {
|
||||
typedef SPI SpiType;
|
||||
typedef Cmt2300a<SpiType> CmtType;
|
||||
|
@ -28,23 +28,25 @@ class CmtRadio {
|
|||
mDtuSn = DTU_SN;
|
||||
}
|
||||
|
||||
void setup(bool genDtuSn = true) {
|
||||
if(genDtuSn)
|
||||
generateDtuSn();
|
||||
if(!mCmt.reset())
|
||||
DPRINTLN(DBG_WARN, F("Initializing CMT2300A failed!"));
|
||||
else
|
||||
mCmt.goRx();
|
||||
void setup(uint8_t pinCsb, uint8_t pinFcsb, bool genDtuSn = true) {
|
||||
mCmt.setup(pinCsb, pinFcsb);
|
||||
reset(genDtuSn);
|
||||
}
|
||||
|
||||
mSendCnt = 0;
|
||||
mRetransmits = 0;
|
||||
mSerialDebug = false;
|
||||
mIvIdChannelSet = NULL;
|
||||
mIrqRcvd = false;
|
||||
void setup(bool genDtuSn = true) {
|
||||
mCmt.setup();
|
||||
reset(genDtuSn);
|
||||
}
|
||||
|
||||
bool loop() {
|
||||
mCmt.loop();
|
||||
|
||||
if(++mCnt > 30000) {
|
||||
mCnt = 0;
|
||||
if(NULL != mIvIdChannelSet)
|
||||
prepareSwitchChannelCmd(mIvIdChannelSet);
|
||||
}
|
||||
|
||||
if(!mIrqRcvd)
|
||||
return false;
|
||||
mIrqRcvd = false;
|
||||
|
@ -54,8 +56,6 @@ class CmtRadio {
|
|||
}
|
||||
|
||||
void tickSecond() {
|
||||
if(NULL != mIvIdChannelSet)
|
||||
prepareSwitchChannelCmd(mIvIdChannelSet);
|
||||
}
|
||||
|
||||
void handleIntr(void) {
|
||||
|
@ -66,28 +66,24 @@ class CmtRadio {
|
|||
mSerialDebug = true;
|
||||
}
|
||||
|
||||
void setIvBackChannel(const uint32_t *ivId) {
|
||||
void setIvBackChannel(const uint64_t *ivId) {
|
||||
mIvIdChannelSet = ivId;
|
||||
prepareSwitchChannelCmd(mIvIdChannelSet);
|
||||
|
||||
}
|
||||
|
||||
void prepareDevInformCmd(const uint32_t *ivId, 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(const uint64_t *ivId, 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.
|
||||
initPacket(ivId, reqfld, ALL_FRAMES);
|
||||
mTxBuf[10] = cmd;
|
||||
mTxBuf[12] = U32_B3(ts);
|
||||
mTxBuf[13] = U32_B2(ts);
|
||||
mTxBuf[14] = U32_B1(ts);
|
||||
mTxBuf[15] = U32_B0(ts);
|
||||
CP_U32_LittleEndian(&mTxBuf[12], ts);
|
||||
/*if (cmd == RealTimeRunData_Debug || cmd == AlarmData ) {
|
||||
mTxBuf[18] = (alarmMesId >> 8) & 0xff;
|
||||
mTxBuf[19] = (alarmMesId ) & 0xff;
|
||||
}*/
|
||||
mCmt.swichChannel(true);
|
||||
sendPacket(24, isRetransmit);
|
||||
}
|
||||
|
||||
inline void prepareSwitchChannelCmd(const uint32_t *ivId, uint8_t freqSel = 0x0c) {
|
||||
inline void prepareSwitchChannelCmd(const uint64_t *ivId, uint8_t freqSel = 0x0c) {
|
||||
/** freqSel:
|
||||
* 0x0c: 863.00 MHz
|
||||
* 0x0d: 863.24 MHz
|
||||
|
@ -100,7 +96,6 @@ class CmtRadio {
|
|||
mTxBuf[11] = 0x21;
|
||||
mTxBuf[12] = freqSel;
|
||||
mTxBuf[13] = 0x14;
|
||||
mCmt.swichChannel();
|
||||
sendPacket(14, false);
|
||||
}
|
||||
|
||||
|
@ -124,6 +119,8 @@ class CmtRadio {
|
|||
if(CMT_SUCCESS != status) {
|
||||
DPRINT(DBG_WARN, F("CMT TX failed, code: "));
|
||||
DBGPRINTLN(String(status));
|
||||
if(CMT_ERR_RX_IN_FIFO == status)
|
||||
mIrqRcvd = true;
|
||||
}
|
||||
|
||||
if(isRetransmit)
|
||||
|
@ -137,16 +134,26 @@ class CmtRadio {
|
|||
std::queue<hmsPacket_t> mBufCtrl;
|
||||
|
||||
private:
|
||||
void initPacket(const uint32_t *ivId, uint8_t mid, uint8_t pid) {
|
||||
inline void reset(bool genDtuSn) {
|
||||
if(genDtuSn)
|
||||
generateDtuSn();
|
||||
if(!mCmt.reset())
|
||||
DPRINTLN(DBG_WARN, F("Initializing CMT2300A failed!"));
|
||||
else
|
||||
mCmt.goRx();
|
||||
|
||||
mSendCnt = 0;
|
||||
mRetransmits = 0;
|
||||
mSerialDebug = false;
|
||||
mIvIdChannelSet = NULL;
|
||||
mIrqRcvd = false;
|
||||
mCnt = 0;
|
||||
}
|
||||
|
||||
void initPacket(const uint64_t *ivId, uint8_t mid, uint8_t pid) {
|
||||
mTxBuf[0] = mid;
|
||||
mTxBuf[1] = U32_B3(*ivId);
|
||||
mTxBuf[2] = U32_B2(*ivId);
|
||||
mTxBuf[3] = U32_B1(*ivId);
|
||||
mTxBuf[4] = U32_B0(*ivId);
|
||||
mTxBuf[5] = U32_B3(mDtuSn);
|
||||
mTxBuf[6] = U32_B2(mDtuSn);
|
||||
mTxBuf[7] = U32_B1(mDtuSn);
|
||||
mTxBuf[8] = U32_B0(mDtuSn);
|
||||
CP_U32_BigEndian(&mTxBuf[1], (*ivId) >> 8);
|
||||
CP_U32_LittleEndian(&mTxBuf[5], mDtuSn);
|
||||
mTxBuf[9] = pid;
|
||||
memset(&mTxBuf[10], 0x00, 17);
|
||||
}
|
||||
|
@ -170,15 +177,15 @@ class CmtRadio {
|
|||
if(CMT_SUCCESS == status)
|
||||
mBufCtrl.push(p);
|
||||
if(NULL != mIvIdChannelSet) {
|
||||
if(U32_B3(*mIvIdChannelSet) != p.data[2])
|
||||
if(U32_B3((*mIvIdChannelSet) >> 8) != p.data[2])
|
||||
return;
|
||||
if(U32_B2(*mIvIdChannelSet) != p.data[3])
|
||||
if(U32_B2((*mIvIdChannelSet) >> 8) != p.data[3])
|
||||
return;
|
||||
if(U32_B1(*mIvIdChannelSet) != p.data[4])
|
||||
if(U32_B1((*mIvIdChannelSet) >> 8) != p.data[4])
|
||||
return;
|
||||
if(U32_B0(*mIvIdChannelSet) != p.data[5])
|
||||
if(U32_B0((*mIvIdChannelSet) >> 8) != p.data[5])
|
||||
return;
|
||||
*mIvIdChannelSet = NULL;
|
||||
mIvIdChannelSet = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -186,8 +193,10 @@ class CmtRadio {
|
|||
uint32_t mDtuSn;
|
||||
uint8_t mTxBuf[27];
|
||||
bool mSerialDebug;
|
||||
uint32_t *mIvIdChannelSet;
|
||||
const uint64_t *mIvIdChannelSet;
|
||||
bool mIrqRcvd;
|
||||
|
||||
uint16_t mCnt;
|
||||
};
|
||||
|
||||
#endif /*__HMS_RADIO_H__*/
|
||||
|
|
|
@ -22,10 +22,14 @@ IRAM_ATTR void handleHmsIntr(void) {
|
|||
void setup() {
|
||||
myApp.setup();
|
||||
|
||||
if(myApp.getNrfEnabled())
|
||||
if(myApp.getNrfEnabled()) {
|
||||
if(DEF_PIN_OFF != myApp.getNrfIrqPin())
|
||||
attachInterrupt(digitalPinToInterrupt(myApp.getNrfIrqPin()), handleIntr, FALLING);
|
||||
if(myApp.getCmtEnabled())
|
||||
}
|
||||
if(myApp.getCmtEnabled()) {
|
||||
if(DEF_PIN_OFF != myApp.getCmtIrqPin())
|
||||
attachInterrupt(digitalPinToInterrupt(myApp.getCmtIrqPin()), handleHmsIntr, RISING);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -16,6 +16,22 @@
|
|||
|
||||
#define CHECK_MASK(a,b) ((a & b) == b)
|
||||
|
||||
#define CP_U32_LittleEndian(buf, v) ({ \
|
||||
uint8_t *b = buf; \
|
||||
b[0] = ((v >> 24) & 0xff); \
|
||||
b[1] = ((v >> 16) & 0xff); \
|
||||
b[2] = ((v >> 8) & 0xff); \
|
||||
b[3] = ((v ) & 0xff); \
|
||||
})
|
||||
|
||||
#define CP_U32_BigEndian(buf, v) ({ \
|
||||
uint8_t *b = buf; \
|
||||
b[3] = ((v >> 24) & 0xff); \
|
||||
b[2] = ((v >> 16) & 0xff); \
|
||||
b[1] = ((v >> 8) & 0xff); \
|
||||
b[0] = ((v ) & 0xff); \
|
||||
})
|
||||
|
||||
namespace ah {
|
||||
void ip2Arr(uint8_t ip[], const char *ipStr);
|
||||
void ip2Char(uint8_t ip[], char *str);
|
||||
|
|
|
@ -297,7 +297,7 @@
|
|||
[39, "VN (GPIO39)"]
|
||||
];
|
||||
|
||||
const re = /11[2,4,6]1.*/;
|
||||
const re = /11[2,4,6][1,2,4].*/;
|
||||
|
||||
document.getElementById("btnAdd").addEventListener("click", function() {
|
||||
if(highestId <= (maxInv-1)) {
|
||||
|
@ -383,8 +383,7 @@
|
|||
iv.appendChild(lbl(id + "Enable", "Communication Enable"));
|
||||
var en = inp(id + "Enable", null, null, ["cb"], id + "Enable", "checkbox");
|
||||
en.checked = obj["enabled"];
|
||||
iv.appendChild(en);
|
||||
iv.appendChild(br());
|
||||
iv.append(en, br());
|
||||
|
||||
iv.appendChild(lbl(id + "Addr", "Serial Number (12 digits)*"));
|
||||
var addr = inp(id + "Addr", obj["serial"], 12, ["text"], null, "text", "[0-9]+", "Invalid input");
|
||||
|
@ -410,9 +409,8 @@
|
|||
case "4": max = 2; break;
|
||||
case "6": max = 4; break;
|
||||
}
|
||||
}
|
||||
else if(serial.charAt(2) == 6) {
|
||||
switch(serial.charAt(3) == 4) {
|
||||
} else if(serial.charAt(2) == 6) {
|
||||
switch(serial.charAt(3)) {
|
||||
case "4": max = 4; break;
|
||||
}
|
||||
}
|
||||
|
@ -536,14 +534,14 @@
|
|||
}
|
||||
}
|
||||
|
||||
function parseNrfRadio(obj) {
|
||||
function parseNrfRadio(obj, type) {
|
||||
var e = document.getElementById("rf24");
|
||||
var en = inp("rf24Enable", null, null, ["cb"], "rf24Enable", "checkbox");
|
||||
en.checked = obj["en"];
|
||||
|
||||
e.append(
|
||||
lbl("rf24Enable", "NRF24 Radio Enable"),
|
||||
en,
|
||||
lbl("rf24Enable", "NRF24 Enable"),
|
||||
en, br(),
|
||||
lbl("rf24Power", "Amplifier Power Level"),
|
||||
sel("rf24Power", [
|
||||
[0, "MIN"],
|
||||
|
@ -561,14 +559,14 @@
|
|||
}
|
||||
}
|
||||
|
||||
function parseCmtRadio(obj) {
|
||||
function parseCmtRadio(obj, type) {
|
||||
var e = document.getElementById("cmt");
|
||||
var en = inp("cmtEnable", null, null, ["cb"], "cmtEnable", "checkbox");
|
||||
en.checked = obj["en"];
|
||||
|
||||
e.append(
|
||||
lbl("cmtEnable", "CMT2300A Radio Enable"),
|
||||
en
|
||||
lbl("cmtEnable", "CMT2300A Enable"),
|
||||
en, br()
|
||||
);
|
||||
pins = [['csb', 'pinCsb'], ['fcsb', 'pinFcsb'], ['irq', 'pinGpio3']];
|
||||
for(p of pins) {
|
||||
|
@ -619,9 +617,9 @@
|
|||
parseNtp(root["ntp"]);
|
||||
parseSun(root["sun"]);
|
||||
parsePinout(root["pinout"], root["system"]["esp_type"]);
|
||||
parseNrfRadio(root["radioNrf"]);
|
||||
parseNrfRadio(root["radioNrf"], root["system"]["esp_type"]);
|
||||
if(root["generic"]["esp_type"] == "ESP32")
|
||||
parseCmtRadio(root["radioCmt"]);
|
||||
parseCmtRadio(root["radioCmt"], root["system"]["esp_type"]);
|
||||
parseSerial(root["serial"]);
|
||||
parseDisplay(root["display"], root["system"]["esp_type"]);
|
||||
}
|
||||
|
@ -635,8 +633,7 @@
|
|||
for(i = 0; i < root["networks"].length; i++) {
|
||||
s.appendChild(opt(root["networks"][i]["ssid"], root["networks"][i]["ssid"] + " (" + root["networks"][i]["rssi"] + " dBm)"));
|
||||
}
|
||||
}
|
||||
else
|
||||
} else
|
||||
s.appendChild(opt("-1", "no network found"));
|
||||
}
|
||||
|
||||
|
|
|
@ -506,10 +506,10 @@ class Web {
|
|||
|
||||
// pinout
|
||||
uint8_t pin;
|
||||
for(uint8_t i = 0; i < 5; i ++) {
|
||||
for(uint8_t i = 0; i < 8; i ++) {
|
||||
pin = request->arg(String(pinArgNames[i])).toInt();
|
||||
switch(i) {
|
||||
default: mConfig->nrf.pinCs = ((pin != 0xff) ? pin : DEF_CS_PIN); break;
|
||||
case 0: mConfig->nrf.pinCs = ((pin != 0xff) ? pin : DEF_CS_PIN); break;
|
||||
case 1: mConfig->nrf.pinCe = ((pin != 0xff) ? pin : DEF_CE_PIN); break;
|
||||
case 2: mConfig->nrf.pinIrq = ((pin != 0xff) ? pin : DEF_IRQ_PIN); break;
|
||||
case 3: mConfig->led.led0 = pin; break;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue