Browse Source

Merge branch 'development03' into Zero-Export

pull/1155/head
DanielR92 2 years ago
parent
commit
3255bc076c
  1. 2
      .github/workflows/compile_development.yml
  2. 2
      .github/workflows/compile_release.yml
  3. 981
      patches/RF24_Hal.patch
  4. 3
      scripts/applyPatches.py
  5. 13
      scripts/getVersion.py
  6. 66
      src/CHANGES.md
  7. 32
      src/app.cpp
  8. 22
      src/app.h
  9. 7
      src/appInterface.h
  10. 26
      src/config/config.h
  11. 54
      src/config/settings.h
  12. 2
      src/defines.h
  13. 56
      src/eth/ahoyeth.cpp
  14. 4
      src/eth/ahoyeth.h
  15. 141
      src/eth/ethSpi.h
  16. 9
      src/hm/CommQueue.h
  17. 370
      src/hm/Communication.h
  18. 166
      src/hm/Heuristic.h
  19. 32
      src/hm/HeuristicInv.h
  20. 11
      src/hm/hmInverter.h
  21. 134
      src/hm/hmRadio.h
  22. 218
      src/hm/nrfHal.h
  23. 13
      src/hm/radio.h
  24. 19
      src/hms/cmt2300a.h
  25. 196
      src/hms/cmtHal.h
  26. 2
      src/hms/esp32_3wSpi.h
  27. 20
      src/hms/hmsRadio.h
  28. 42
      src/platformio.ini
  29. 137
      src/plugins/Display/Display.h
  30. 77
      src/plugins/Display/Display_Mono.h
  31. 36
      src/plugins/Display/Display_Mono_128X32.h
  32. 230
      src/plugins/Display/Display_Mono_128X64.h
  33. 38
      src/plugins/Display/Display_Mono_64X48.h
  34. 83
      src/plugins/Display/Display_Mono_84X48.h
  35. 4
      src/plugins/Display/Display_data.h
  36. 4
      src/publisher/pubMqtt.h
  37. 11
      src/utils/helper.cpp
  38. 1
      src/utils/helper.h
  39. 11
      src/utils/scheduler.h
  40. 9
      src/utils/spiPatcher.cpp
  41. 88
      src/utils/spiPatcher.h
  42. 17
      src/utils/spiPatcherHandle.h
  43. 34
      src/web/RestApi.h
  44. 20
      src/web/html/serial.html
  45. 89
      src/web/html/setup.html
  46. 8
      src/web/html/system.html
  47. 5
      src/web/html/update.html
  48. 3
      src/web/html/visualization.html
  49. 25
      src/web/web.h
  50. 19
      src/wifi/ahoywifi.cpp
  51. 11
      tools/fonts/u8g2_font_5x8_symbols_ahoy.bdf
  52. 10
      tools/fonts/u8g2_font_5x8_symbols_ahoy.c_
  53. BIN
      tools/fonts/u8g2_font_5x8_symbols_ahoy.fon
  54. 32
      tools/fonts/u8g2_font_ncenB10_symbols10_ahoy.bdf
  55. 14
      tools/fonts/u8g2_font_ncenB10_symbols10_ahoy.c_
  56. BIN
      tools/fonts/u8g2_font_ncenB10_symbols10_ahoy.fon

2
.github/workflows/compile_development.yml

@ -43,7 +43,7 @@ jobs:
pip install --upgrade platformio
- name: Run PlatformIO
run: pio run -d src --environment esp8266 --environment esp8266-prometheus --environment esp8285 --environment esp32-wroom32 --environment esp32-wroom32-prometheus --environment esp32-wroom32-ethernet --environment esp32-s2-mini --environment opendtufusion
run: pio run -d src --environment esp8266 --environment esp8266-prometheus --environment esp8285 --environment esp32-wroom32 --environment esp32-wroom32-prometheus --environment esp32-wroom32-ethernet --environment esp32-s2-mini --environment opendtufusion --environment opendtufusion-ethernet
- name: Copy boot_app0.bin
run: cp ~/.platformio/packages/framework-arduinoespressif32/tools/partitions/boot_app0.bin src/.pio/build/opendtufusion/ota.bin

2
.github/workflows/compile_release.yml

@ -47,7 +47,7 @@ jobs:
pip install --upgrade platformio
- name: Run PlatformIO
run: pio run -d src --environment esp8266 --environment esp8266-prometheus --environment esp8285 --environment esp32-wroom32 --environment esp32-wroom32-prometheus --environment esp32-wroom32-ethernet --environment esp32-s2-mini --environment opendtufusion
run: pio run -d src --environment esp8266 --environment esp8266-prometheus --environment esp8285 --environment esp32-wroom32 --environment esp32-wroom32-prometheus --environment esp32-wroom32-ethernet --environment esp32-s2-mini --environment opendtufusion --environment opendtufusion-ethernet
- name: Copy boot_app0.bin
run: cp ~/.platformio/packages/framework-arduinoespressif32/tools/partitions/boot_app0.bin src/.pio/build/opendtufusion/ota.bin

981
patches/RF24_Hal.patch

@ -0,0 +1,981 @@
diff --git a/RF24.cpp b/RF24.cpp
index c0cc732..b6708d9 100644
--- a/RF24.cpp
+++ b/RF24.cpp
@@ -12,228 +12,24 @@
/****************************************************************************/
-void RF24::csn(bool mode)
-{
-#if defined(RF24_TINY)
- if (ce_pin != csn_pin) {
- digitalWrite(csn_pin, mode);
- }
- else {
- if (mode == HIGH) {
- PORTB |= (1 << PINB2); // SCK->CSN HIGH
- delayMicroseconds(RF24_CSN_SETTLE_HIGH_DELAY); // allow csn to settle.
- }
- else {
- PORTB &= ~(1 << PINB2); // SCK->CSN LOW
- delayMicroseconds(RF24_CSN_SETTLE_LOW_DELAY); // allow csn to settle
- }
- }
- // Return, CSN toggle complete
- return;
-
-#elif defined(ARDUINO) && !defined(RF24_SPI_TRANSACTIONS)
- // Minimum ideal SPI bus speed is 2x data rate
- // If we assume 2Mbs data rate and 16Mhz clock, a
- // divider of 4 is the minimum we want.
- // CLK:BUS 8Mhz:2Mhz, 16Mhz:4Mhz, or 20Mhz:5Mhz
-
- #if !defined(SOFTSPI)
- // applies to SPI_UART and inherent hardware SPI
- #if defined(RF24_SPI_PTR)
- _spi->setBitOrder(MSBFIRST);
- _spi->setDataMode(SPI_MODE0);
-
- #if !defined(F_CPU) || F_CPU < 20000000
- _spi->setClockDivider(SPI_CLOCK_DIV2);
- #elif F_CPU < 40000000
- _spi->setClockDivider(SPI_CLOCK_DIV4);
- #elif F_CPU < 80000000
- _spi->setClockDivider(SPI_CLOCK_DIV8);
- #elif F_CPU < 160000000
- _spi->setClockDivider(SPI_CLOCK_DIV16);
- #elif F_CPU < 320000000
- _spi->setClockDivider(SPI_CLOCK_DIV32);
- #elif F_CPU < 640000000
- _spi->setClockDivider(SPI_CLOCK_DIV64);
- #elif F_CPU < 1280000000
- _spi->setClockDivider(SPI_CLOCK_DIV128);
- #else // F_CPU >= 1280000000
- #error "Unsupported CPU frequency. Please set correct SPI divider."
- #endif // F_CPU to SPI_CLOCK_DIV translation
-
- #else // !defined(RF24_SPI_PTR)
- _SPI.setBitOrder(MSBFIRST);
- _SPI.setDataMode(SPI_MODE0);
-
- #if !defined(F_CPU) || F_CPU < 20000000
- _SPI.setClockDivider(SPI_CLOCK_DIV2);
- #elif F_CPU < 40000000
- _SPI.setClockDivider(SPI_CLOCK_DIV4);
- #elif F_CPU < 80000000
- _SPI.setClockDivider(SPI_CLOCK_DIV8);
- #elif F_CPU < 160000000
- _SPI.setClockDivider(SPI_CLOCK_DIV16);
- #elif F_CPU < 320000000
- _SPI.setClockDivider(SPI_CLOCK_DIV32);
- #elif F_CPU < 640000000
- _SPI.setClockDivider(SPI_CLOCK_DIV64);
- #elif F_CPU < 1280000000
- _SPI.setClockDivider(SPI_CLOCK_DIV128);
- #else // F_CPU >= 1280000000
- #error "Unsupported CPU frequency. Please set correct SPI divider."
- #endif // F_CPU to SPI_CLOCK_DIV translation
- #endif // !defined(RF24_SPI_PTR)
- #endif // !defined(SOFTSPI)
-
-#elif defined(RF24_RPi)
- if (!mode)
- _SPI.chipSelect(csn_pin);
-#endif // defined(RF24_RPi)
-
-#if !defined(RF24_LINUX)
- digitalWrite(csn_pin, mode);
- delayMicroseconds(csDelay);
-#else
- static_cast<void>(mode); // ignore -Wunused-parameter
-#endif // !defined(RF24_LINUX)
-}
-
-/****************************************************************************/
-
void RF24::ce(bool level)
{
-#ifndef RF24_LINUX
- //Allow for 3-pin use on ATTiny
- if (ce_pin != csn_pin) {
-#endif
- digitalWrite(ce_pin, level);
-#ifndef RF24_LINUX
- }
-#endif
-}
-
-/****************************************************************************/
-
-inline void RF24::beginTransaction()
-{
-#if defined(RF24_SPI_TRANSACTIONS)
- #if defined(RF24_SPI_PTR)
- #if defined(RF24_RP2)
- _spi->beginTransaction(spi_speed);
- #else // ! defined (RF24_RP2)
- _spi->beginTransaction(SPISettings(spi_speed, MSBFIRST, SPI_MODE0));
- #endif // ! defined (RF24_RP2)
- #else // !defined(RF24_SPI_PTR)
- _SPI.beginTransaction(SPISettings(spi_speed, MSBFIRST, SPI_MODE0));
- #endif // !defined(RF24_SPI_PTR)
-#endif // defined (RF24_SPI_TRANSACTIONS)
- csn(LOW);
-}
-
-/****************************************************************************/
-
-inline void RF24::endTransaction()
-{
- csn(HIGH);
-#if defined(RF24_SPI_TRANSACTIONS)
- #if defined(RF24_SPI_PTR)
- _spi->endTransaction();
- #else // !defined(RF24_SPI_PTR)
- _SPI.endTransaction();
- #endif // !defined(RF24_SPI_PTR)
-#endif // defined (RF24_SPI_TRANSACTIONS)
+ hal->ce(level);
}
/****************************************************************************/
void RF24::read_register(uint8_t reg, uint8_t* buf, uint8_t len)
{
-#if defined(RF24_LINUX) || defined(RF24_RP2)
- beginTransaction(); //configures the spi settings for RPi, locks mutex and setting csn low
- uint8_t* prx = spi_rxbuff;
- uint8_t* ptx = spi_txbuff;
- uint8_t size = static_cast<uint8_t>(len + 1); // Add register value to transmit buffer
-
- *ptx++ = (R_REGISTER | reg);
-
- while (len--) {
- *ptx++ = RF24_NOP; // Dummy operation, just for reading
- }
-
- #if defined(RF24_RP2)
- _spi->transfernb((const uint8_t*)spi_txbuff, spi_rxbuff, size);
- #else // !defined (RF24_RP2)
- _SPI.transfernb(reinterpret_cast<char*>(spi_txbuff), reinterpret_cast<char*>(spi_rxbuff), size);
- #endif // !defined (RF24_RP2)
-
- status = *prx++; // status is 1st byte of receive buffer
-
- // decrement before to skip status byte
- while (--size) {
- *buf++ = *prx++;
- }
-
- endTransaction(); // unlocks mutex and setting csn high
-
-#else // !defined(RF24_LINUX) && !defined(RF24_RP2)
-
- beginTransaction();
- #if defined(RF24_SPI_PTR)
- status = _spi->transfer(R_REGISTER | reg);
- while (len--) {
- *buf++ = _spi->transfer(0xFF);
- }
-
- #else // !defined(RF24_SPI_PTR)
- status = _SPI.transfer(R_REGISTER | reg);
- while (len--) {
- *buf++ = _SPI.transfer(0xFF);
- }
-
- #endif // !defined(RF24_SPI_PTR)
- endTransaction();
-#endif // !defined(RF24_LINUX) && !defined(RF24_RP2)
+ status = hal->read(R_REGISTER | reg, buf, len);
}
/****************************************************************************/
uint8_t RF24::read_register(uint8_t reg)
{
- uint8_t result;
-
-#if defined(RF24_LINUX) || defined(RF24_RP2)
- beginTransaction();
-
- uint8_t* prx = spi_rxbuff;
- uint8_t* ptx = spi_txbuff;
- *ptx++ = (R_REGISTER | reg);
- *ptx++ = RF24_NOP; // Dummy operation, just for reading
-
- #if defined(RF24_RP2)
- _spi->transfernb((const uint8_t*)spi_txbuff, spi_rxbuff, 2);
- #else // !defined(RF24_RP2)
- _SPI.transfernb(reinterpret_cast<char*>(spi_txbuff), reinterpret_cast<char*>(spi_rxbuff), 2);
- #endif // !defined(RF24_RP2)
-
- status = *prx; // status is 1st byte of receive buffer
- result = *++prx; // result is 2nd byte of receive buffer
-
- endTransaction();
-#else // !defined(RF24_LINUX) && !defined(RF24_RP2)
-
- beginTransaction();
- #if defined(RF24_SPI_PTR)
- status = _spi->transfer(R_REGISTER | reg);
- result = _spi->transfer(0xff);
-
- #else // !defined(RF24_SPI_PTR)
- status = _SPI.transfer(R_REGISTER | reg);
- result = _SPI.transfer(0xff);
-
- #endif // !defined(RF24_SPI_PTR)
- endTransaction();
-#endif // !defined(RF24_LINUX) && !defined(RF24_RP2)
-
+ uint8_t result = 0xff;
+ status = hal->read(R_REGISTER | reg, &result, sizeof(result));
return result;
}
@@ -241,43 +37,7 @@ uint8_t RF24::read_register(uint8_t reg)
void RF24::write_register(uint8_t reg, const uint8_t* buf, uint8_t len)
{
-#if defined(RF24_LINUX) || defined(RF24_RP2)
- beginTransaction();
- uint8_t* prx = spi_rxbuff;
- uint8_t* ptx = spi_txbuff;
- uint8_t size = static_cast<uint8_t>(len + 1); // Add register value to transmit buffer
-
- *ptx++ = (W_REGISTER | (REGISTER_MASK & reg));
- while (len--) {
- *ptx++ = *buf++;
- }
-
- #if defined(RF24_RP2)
- _spi->transfernb((const uint8_t*)spi_txbuff, spi_rxbuff, size);
- #else // !defined(RF24_RP2)
- _SPI.transfernb(reinterpret_cast<char*>(spi_txbuff), reinterpret_cast<char*>(spi_rxbuff), size);
- #endif // !defined(RF24_RP2)
-
- status = *prx; // status is 1st byte of receive buffer
- endTransaction();
-#else // !defined(RF24_LINUX) && !defined(RF24_RP2)
-
- beginTransaction();
- #if defined(RF24_SPI_PTR)
- status = _spi->transfer(W_REGISTER | reg);
- while (len--) {
- _spi->transfer(*buf++);
- }
-
- #else // !defined(RF24_SPI_PTR)
- status = _SPI.transfer(W_REGISTER | reg);
- while (len--) {
- _SPI.transfer(*buf++);
- }
-
- #endif // !defined(RF24_SPI_PTR)
- endTransaction();
-#endif // !defined(RF24_LINUX) && !defined(RF24_RP2)
+ status = hal->write(W_REGISTER | reg, buf, len);
}
/****************************************************************************/
@@ -288,47 +48,11 @@ void RF24::write_register(uint8_t reg, uint8_t value, bool is_cmd_only)
if (reg != RF24_NOP) { // don't print the get_status() operation
IF_SERIAL_DEBUG(printf_P(PSTR("write_register(%02x)\r\n"), reg));
}
- beginTransaction();
-#if defined(RF24_LINUX)
- status = _SPI.transfer(W_REGISTER | reg);
-#else // !defined(RF24_LINUX) || defined (RF24_RP2)
- #if defined(RF24_SPI_PTR)
- status = _spi->transfer(W_REGISTER | reg);
- #else // !defined (RF24_SPI_PTR)
- status = _SPI.transfer(W_REGISTER | reg);
- #endif // !defined (RF24_SPI_PTR)
-#endif // !defined(RF24_LINUX) || defined(RF24_RP2)
- endTransaction();
+ status = hal->write(W_REGISTER | reg, nullptr, 0);
}
else {
IF_SERIAL_DEBUG(printf_P(PSTR("write_register(%02x,%02x)\r\n"), reg, value));
-#if defined(RF24_LINUX) || defined(RF24_RP2)
- beginTransaction();
- uint8_t* prx = spi_rxbuff;
- uint8_t* ptx = spi_txbuff;
- *ptx++ = (W_REGISTER | reg);
- *ptx = value;
-
- #if defined(RF24_RP2)
- _spi->transfernb((const uint8_t*)spi_txbuff, spi_rxbuff, 2);
- #else // !defined(RF24_RP2)
- _SPI.transfernb(reinterpret_cast<char*>(spi_txbuff), reinterpret_cast<char*>(spi_rxbuff), 2);
- #endif // !defined(RF24_RP2)
-
- status = *prx++; // status is 1st byte of receive buffer
- endTransaction();
-#else // !defined(RF24_LINUX) && !defined(RF24_RP2)
-
- beginTransaction();
- #if defined(RF24_SPI_PTR)
- status = _spi->transfer(W_REGISTER | reg);
- _spi->transfer(value);
- #else // !defined(RF24_SPI_PTR)
- status = _SPI.transfer(W_REGISTER | reg);
- _SPI.transfer(value);
- #endif // !defined(RF24_SPI_PTR)
- endTransaction();
-#endif // !defined(RF24_LINUX) && !defined(RF24_RP2)
+ status = hal->write(W_REGISTER | reg, &value, sizeof(value));
}
}
@@ -347,60 +71,8 @@ void RF24::write_payload(const void* buf, uint8_t data_len, const uint8_t writeT
data_len = rf24_min(data_len, static_cast<uint8_t>(32));
}
- //printf("[Writing %u bytes %u blanks]",data_len,blank_len);
IF_SERIAL_DEBUG(printf("[Writing %u bytes %u blanks]\n", data_len, blank_len););
-
-#if defined(RF24_LINUX) || defined(RF24_RP2)
- beginTransaction();
- uint8_t* prx = spi_rxbuff;
- uint8_t* ptx = spi_txbuff;
- uint8_t size;
- size = static_cast<uint8_t>(data_len + blank_len + 1); // Add register value to transmit buffer
-
- *ptx++ = writeType;
- while (data_len--) {
- *ptx++ = *current++;
- }
-
- while (blank_len--) {
- *ptx++ = 0;
- }
-
- #if defined(RF24_RP2)
- _spi->transfernb((const uint8_t*)spi_txbuff, spi_rxbuff, size);
- #else // !defined(RF24_RP2)
- _SPI.transfernb(reinterpret_cast<char*>(spi_txbuff), reinterpret_cast<char*>(spi_rxbuff), size);
- #endif // !defined(RF24_RP2)
-
- status = *prx; // status is 1st byte of receive buffer
- endTransaction();
-
-#else // !defined(RF24_LINUX) && !defined(RF24_RP2)
-
- beginTransaction();
- #if defined(RF24_SPI_PTR)
- status = _spi->transfer(writeType);
- while (data_len--) {
- _spi->transfer(*current++);
- }
-
- while (blank_len--) {
- _spi->transfer(0);
- }
-
- #else // !defined(RF24_SPI_PTR)
- status = _SPI.transfer(writeType);
- while (data_len--) {
- _SPI.transfer(*current++);
- }
-
- while (blank_len--) {
- _SPI.transfer(0);
- }
-
- #endif // !defined(RF24_SPI_PTR)
- endTransaction();
-#endif // !defined(RF24_LINUX) && !defined(RF24_RP2)
+ status = hal->write(writeType, current, data_len, blank_len);
}
/****************************************************************************/
@@ -421,65 +93,7 @@ void RF24::read_payload(void* buf, uint8_t data_len)
//printf("[Reading %u bytes %u blanks]",data_len,blank_len);
IF_SERIAL_DEBUG(printf("[Reading %u bytes %u blanks]\n", data_len, blank_len););
-
-#if defined(RF24_LINUX) || defined(RF24_RP2)
- beginTransaction();
- uint8_t* prx = spi_rxbuff;
- uint8_t* ptx = spi_txbuff;
- uint8_t size;
- size = static_cast<uint8_t>(data_len + blank_len + 1); // Add register value to transmit buffer
-
- *ptx++ = R_RX_PAYLOAD;
- while (--size) {
- *ptx++ = RF24_NOP;
- }
-
- size = static_cast<uint8_t>(data_len + blank_len + 1); // Size has been lost during while, re affect
-
- #if defined(RF24_RP2)
- _spi->transfernb((const uint8_t*)spi_txbuff, spi_rxbuff, size);
- #else // !defined(RF24_RP2)
- _SPI.transfernb(reinterpret_cast<char*>(spi_txbuff), reinterpret_cast<char*>(spi_rxbuff), size);
- #endif // !defined(RF24_RP2)
-
- status = *prx++; // 1st byte is status
-
- if (data_len > 0) {
- // Decrement before to skip 1st status byte
- while (--data_len) {
- *current++ = *prx++;
- }
-
- *current = *prx;
- }
- endTransaction();
-#else // !defined(RF24_LINUX) && !defined(RF24_RP2)
-
- beginTransaction();
- #if defined(RF24_SPI_PTR)
- status = _spi->transfer(R_RX_PAYLOAD);
- while (data_len--) {
- *current++ = _spi->transfer(0xFF);
- }
-
- while (blank_len--) {
- _spi->transfer(0xFF);
- }
-
- #else // !defined(RF24_SPI_PTR)
- status = _SPI.transfer(R_RX_PAYLOAD);
- while (data_len--) {
- *current++ = _SPI.transfer(0xFF);
- }
-
- while (blank_len--) {
- _SPI.transfer(0xff);
- }
-
- #endif // !defined(RF24_SPI_PTR)
- endTransaction();
-
-#endif // !defined(RF24_LINUX) && !defined(RF24_RP2)
+ status = hal->read(R_RX_PAYLOAD, current, data_len, blank_len);
}
/****************************************************************************/
@@ -577,16 +191,16 @@ uint8_t RF24::sprintf_address_register(char* out_buffer, uint8_t reg, uint8_t qt
/****************************************************************************/
-RF24::RF24(rf24_gpio_pin_t _cepin, rf24_gpio_pin_t _cspin, uint32_t _spi_speed)
- : ce_pin(_cepin), csn_pin(_cspin), spi_speed(_spi_speed), payload_size(32), _is_p_variant(false), _is_p0_rx(false), addr_width(5), dynamic_payloads_enabled(true), csDelay(5)
+RF24::RF24(RF24_hal* _hal)
+ : hal(_hal), payload_size(32), _is_p_variant(false), _is_p0_rx(false), addr_width(5), dynamic_payloads_enabled(true), csDelay(5)
{
_init_obj();
}
/****************************************************************************/
-RF24::RF24(uint32_t _spi_speed)
- : ce_pin(RF24_PIN_INVALID), csn_pin(RF24_PIN_INVALID), spi_speed(_spi_speed), payload_size(32), _is_p_variant(false), _is_p0_rx(false), addr_width(5), dynamic_payloads_enabled(true), csDelay(5)
+RF24::RF24()
+ : hal(nullptr), payload_size(32), _is_p_variant(false), _is_p0_rx(false), addr_width(5), dynamic_payloads_enabled(true), csDelay(5)
{
_init_obj();
}
@@ -595,16 +209,7 @@ RF24::RF24(uint32_t _spi_speed)
void RF24::_init_obj()
{
- // Use a pointer on the Arduino platform
-
-#if defined(RF24_SPI_PTR) && !defined(RF24_RP2)
- _spi = &SPI;
-#endif // defined (RF24_SPI_PTR)
-
pipe0_reading_address[0] = 0;
- if (spi_speed <= 35000) { //Handle old BCM2835 speed constants, default to RF24_SPI_SPEED
- spi_speed = RF24_SPI_SPEED;
- }
}
/****************************************************************************/
@@ -677,19 +282,6 @@ static const PROGMEM char* const rf24_pa_dbm_e_str_P[] = {
rf24_pa_dbm_e_str_3,
};
- #if defined(RF24_LINUX)
-static const char rf24_csn_e_str_0[] = "CE0 (PI Hardware Driven)";
-static const char rf24_csn_e_str_1[] = "CE1 (PI Hardware Driven)";
-static const char rf24_csn_e_str_2[] = "CE2 (PI Hardware Driven)";
-static const char rf24_csn_e_str_3[] = "Custom GPIO Software Driven";
-static const char* const rf24_csn_e_str_P[] = {
- rf24_csn_e_str_0,
- rf24_csn_e_str_1,
- rf24_csn_e_str_2,
- rf24_csn_e_str_3,
-};
- #endif // defined(RF24_LINUX)
-
static const PROGMEM char rf24_feature_e_str_on[] = "= Enabled";
static const PROGMEM char rf24_feature_e_str_allowed[] = "= Allowed";
static const PROGMEM char rf24_feature_e_str_open[] = " open ";
@@ -704,19 +296,6 @@ static const PROGMEM char* const rf24_feature_e_str_P[] = {
void RF24::printDetails(void)
{
-
- #if defined(RF24_LINUX)
- printf("================ SPI Configuration ================\n");
- uint8_t bus_ce = static_cast<uint8_t>(csn_pin % 10);
- uint8_t bus_numb = static_cast<uint8_t>((csn_pin - bus_ce) / 10);
- printf("CSN Pin\t\t= /dev/spidev%d.%d\n", bus_numb, bus_ce);
- printf("CE Pin\t\t= Custom GPIO%d\n", ce_pin);
- #endif
- printf_P(PSTR("SPI Speedz\t= %d Mhz\n"), static_cast<uint8_t>(spi_speed / 1000000)); //Print the SPI speed on non-Linux devices
- #if defined(RF24_LINUX)
- printf("================ NRF Configuration ================\n");
- #endif // defined(RF24_LINUX)
-
print_status(get_status());
print_address_register(PSTR("RX_ADDR_P0-1"), RX_ADDR_P0, 2);
@@ -748,19 +327,6 @@ void RF24::printDetails(void)
void RF24::printPrettyDetails(void)
{
-
- #if defined(RF24_LINUX)
- printf("================ SPI Configuration ================\n");
- uint8_t bus_ce = static_cast<uint8_t>(csn_pin % 10);
- uint8_t bus_numb = static_cast<uint8_t>((csn_pin - bus_ce) / 10);
- printf("CSN Pin\t\t\t= /dev/spidev%d.%d\n", bus_numb, bus_ce);
- printf("CE Pin\t\t\t= Custom GPIO%d\n", ce_pin);
- #endif
- printf_P(PSTR("SPI Frequency\t\t= %d Mhz\n"), static_cast<uint8_t>(spi_speed / 1000000)); //Print the SPI speed on non-Linux devices
- #if defined(RF24_LINUX)
- printf("================ NRF Configuration ================\n");
- #endif // defined(RF24_LINUX)
-
uint8_t channel = getChannel();
uint16_t frequency = static_cast<uint16_t>(channel + 2400);
printf_P(PSTR("Channel\t\t\t= %u (~ %u MHz)\r\n"), channel, frequency);
@@ -846,11 +412,6 @@ void RF24::printPrettyDetails(void)
uint16_t RF24::sprintfPrettyDetails(char* debugging_information)
{
const char* format_string = PSTR(
- "================ SPI Configuration ================\n"
- "CSN Pin\t\t\t= %d\n"
- "CE Pin\t\t\t= %d\n"
- "SPI Frequency\t\t= %d Mhz\n"
- "================ NRF Configuration ================\n"
"Channel\t\t\t= %u (~ %u MHz)\n"
"RF Data Rate\t\t" PRIPSTR "\n"
"RF Power Amplifier\t" PRIPSTR "\n"
@@ -870,8 +431,7 @@ uint16_t RF24::sprintfPrettyDetails(char* debugging_information)
const char* format_str3 = PSTR("\nPipe %d (" PRIPSTR ") bound\t= 0x");
uint16_t offset = sprintf_P(
- debugging_information, format_string, csn_pin, ce_pin,
- static_cast<uint8_t>(spi_speed / 1000000), getChannel(),
+ debugging_information, format_string, getChannel(),
static_cast<uint16_t>(getChannel() + 2400),
(char*)(pgm_read_ptr(&rf24_datarate_e_str_P[getDataRate()])),
(char*)(pgm_read_ptr(&rf24_pa_dbm_e_str_P[getPALevel()])),
@@ -940,87 +500,26 @@ void RF24::encodeRadioDetails(uint8_t* encoded_details)
*encoded_details++ = read_register(i);
}
}
- *encoded_details++ = ce_pin >> 4;
- *encoded_details++ = ce_pin & 0xFF;
- *encoded_details++ = csn_pin >> 4;
- *encoded_details++ = csn_pin & 0xFF;
- *encoded_details = static_cast<uint8_t>((spi_speed / 1000000) | _BV(_is_p_variant * 4));
}
#endif // !defined(MINIMAL)
/****************************************************************************/
-#if defined(RF24_SPI_PTR) || defined(DOXYGEN_FORCED)
-// does not apply to RF24_LINUX
-bool RF24::begin(_SPI* spiBus)
+bool RF24::begin(void)
{
- _spi = spiBus;
return _init_pins() && _init_radio();
}
/****************************************************************************/
-bool RF24::begin(_SPI* spiBus, rf24_gpio_pin_t _cepin, rf24_gpio_pin_t _cspin)
+bool RF24::begin(RF24_hal* _hal)
{
- ce_pin = _cepin;
- csn_pin = _cspin;
- return begin(spiBus);
-}
-
-#endif // defined (RF24_SPI_PTR) || defined (DOXYGEN_FORCED)
-
-/****************************************************************************/
-
-bool RF24::begin(rf24_gpio_pin_t _cepin, rf24_gpio_pin_t _cspin)
-{
- ce_pin = _cepin;
- csn_pin = _cspin;
+ hal = _hal;
return begin();
}
/****************************************************************************/
-bool RF24::begin(void)
-{
-#if defined(RF24_LINUX)
- #if defined(RF24_RPi)
- switch (csn_pin) { // Ensure valid hardware CS pin
- case 0: break;
- case 1: break;
- // Allow BCM2835 enums for RPi
- case 8: csn_pin = 0; break;
- case 7: csn_pin = 1; break;
- case 18: csn_pin = 10; break; // to make it work on SPI1
- case 17: csn_pin = 11; break;
- case 16: csn_pin = 12; break;
- default: csn_pin = 0; break;
- }
- #endif // RF24_RPi
-
- _SPI.begin(csn_pin, spi_speed);
-
-#elif defined(XMEGA_D3)
- _spi->begin(csn_pin);
-
-#elif defined(RF24_RP2)
- _spi = new SPI();
- _spi->begin(PICO_DEFAULT_SPI ? spi1 : spi0);
-
-#else // using an Arduino platform || defined (LITTLEWIRE)
-
- #if defined(RF24_SPI_PTR)
- _spi->begin();
- #else // !defined(RF24_SPI_PTR)
- _SPI.begin();
- #endif // !defined(RF24_SPI_PTR)
-
-#endif // !defined(XMEGA_D3) && !defined(RF24_LINUX)
-
- return _init_pins() && _init_radio();
-}
-
-/****************************************************************************/
-
bool RF24::_init_pins()
{
if (!isValid()) {
@@ -1028,46 +527,7 @@ bool RF24::_init_pins()
return false;
}
-#if defined(RF24_LINUX)
-
- #if defined(MRAA)
- GPIO();
- gpio.begin(ce_pin, csn_pin);
- #endif
-
- pinMode(ce_pin, OUTPUT);
- ce(LOW);
- delay(100);
-
-#elif defined(LITTLEWIRE)
- pinMode(csn_pin, OUTPUT);
- csn(HIGH);
-
-#elif defined(XMEGA_D3)
- if (ce_pin != csn_pin) {
- pinMode(ce_pin, OUTPUT);
- };
- ce(LOW);
- csn(HIGH);
- delay(200);
-
-#else // using an Arduino platform
-
- // Initialize pins
- if (ce_pin != csn_pin) {
- pinMode(ce_pin, OUTPUT);
- pinMode(csn_pin, OUTPUT);
- }
-
- ce(LOW);
- csn(HIGH);
-
- #if defined(__ARDUINO_X86__)
- delay(100);
- #endif
-#endif // !defined(XMEGA_D3) && !defined(LITTLEWIRE) && !defined(RF24_LINUX)
-
- return true; // assuming pins are connected properly
+ return hal->begin();
}
/****************************************************************************/
@@ -1151,7 +611,7 @@ bool RF24::isChipConnected()
bool RF24::isValid()
{
- return ce_pin != RF24_PIN_INVALID && csn_pin != RF24_PIN_INVALID;
+ return hal != nullptr;
}
/****************************************************************************/
@@ -1676,15 +1136,8 @@ void RF24::closeReadingPipe(uint8_t pipe)
void RF24::toggle_features(void)
{
- beginTransaction();
-#if defined(RF24_SPI_PTR)
- status = _spi->transfer(ACTIVATE);
- _spi->transfer(0x73);
-#else
- status = _SPI.transfer(ACTIVATE);
- _SPI.transfer(0x73);
-#endif
- endTransaction();
+ uint8_t value = 0x73;
+ status = hal->write(ACTIVATE, &value, sizeof(value));
}
/****************************************************************************/
diff --git a/RF24.h b/RF24.h
index dbd32ae..f774bba 100644
--- a/RF24.h
+++ b/RF24.h
@@ -16,12 +16,7 @@
#define __RF24_H__
#include "RF24_config.h"
-
-#if defined(RF24_LINUX) || defined(LITTLEWIRE)
- #include "utility/includes.h"
-#elif defined SOFTSPI
- #include <DigitalIO.h>
-#endif
+#include "RF24_hal.h"
/**
* @defgroup PALevel Power Amplifier level
@@ -115,29 +110,8 @@ typedef enum
class RF24
{
private:
-#ifdef SOFTSPI
- SoftSPI<SOFT_SPI_MISO_PIN, SOFT_SPI_MOSI_PIN, SOFT_SPI_SCK_PIN, SPI_MODE> spi;
-#elif defined(SPI_UART)
- SPIUARTClass uspi;
-#endif
-
-#if defined(RF24_LINUX) || defined(XMEGA_D3) /* XMEGA can use SPI class */
- SPI spi;
-#endif // defined (RF24_LINUX) || defined (XMEGA_D3)
-#if defined(RF24_SPI_PTR)
- _SPI* _spi;
-#endif // defined (RF24_SPI_PTR)
-#if defined(MRAA)
- GPIO gpio;
-#endif
+ RF24_hal *hal;
- rf24_gpio_pin_t ce_pin; /* "Chip Enable" pin, activates the RX or TX role */
- rf24_gpio_pin_t csn_pin; /* SPI Chip select */
- uint32_t spi_speed; /* SPI Bus Speed */
-#if defined(RF24_LINUX) || defined(XMEGA_D3) || defined(RF24_RP2)
- uint8_t spi_rxbuff[32 + 1]; //SPI receive buffer (payload max 32 bytes)
- uint8_t spi_txbuff[32 + 1]; //SPI transmit buffer (payload max 32 bytes + 1 byte for the command)
-#endif
uint8_t status; /* The status byte returned from every SPI transaction */
uint8_t payload_size; /* Fixed size of payloads */
uint8_t pipe0_reading_address[5]; /* Last address set on pipe 0 for reading. */
@@ -146,16 +120,6 @@ private:
bool _is_p0_rx; /* For keeping track of pipe 0's usage in user-triggered RX mode. */
protected:
- /**
- * SPI transactions
- *
- * Common code for SPI transactions including CSN toggle
- *
- */
- inline void beginTransaction();
-
- inline void endTransaction();
-
/** Whether ack payloads are enabled. */
bool ack_payloads_enabled;
/** The address width to use (3, 4 or 5 bytes). */
@@ -198,30 +162,15 @@ public:
*
* See [Related Pages](pages.html) for device specific information
*
- * @param _cepin The pin attached to Chip Enable on the RF module
- * @param _cspin The pin attached to Chip Select (often labeled CSN) on the radio module.
- * - For the Arduino Due board, the [Arduino Due extended SPI feature](https://www.arduino.cc/en/Reference/DueExtendedSPI)
- * is not supported. This means that the Due's pins 4, 10, or 52 are not mandated options (can use any digital output pin) for
- * the radio's CSN pin.
- * @param _spi_speed The SPI speed in Hz ie: 1000000 == 1Mhz
- * - Users can specify default SPI speed by modifying @ref RF24_SPI_SPEED in @ref RF24_config.h
- * - For Arduino, the default SPI speed will only be properly configured this way on devices supporting SPI TRANSACTIONS
- * - Older/Unsupported Arduino devices will use a default clock divider & settings configuration
- * - For Linux: The old way of setting SPI speeds using BCM2835 driver enums has been removed as of v1.3.7
+ * @param _hal A pointer to the device specific hardware abstraction layer
*/
- RF24(rf24_gpio_pin_t _cepin, rf24_gpio_pin_t _cspin, uint32_t _spi_speed = RF24_SPI_SPEED);
+ RF24(RF24_hal *_hal);
/**
* A constructor for initializing the radio's hardware dynamically
- * @warning You MUST use begin(rf24_gpio_pin_t, rf24_gpio_pin_t) or begin(_SPI*, rf24_gpio_pin_t, rf24_gpio_pin_t) to pass both the
- * digital output pin numbers connected to the radio's CE and CSN pins.
- * @param _spi_speed The SPI speed in Hz ie: 1000000 == 1Mhz
- * - Users can specify default SPI speed by modifying @ref RF24_SPI_SPEED in @ref RF24_config.h
- * - For Arduino, the default SPI speed will only be properly configured this way on devices supporting SPI TRANSACTIONS
- * - Older/Unsupported Arduino devices will use a default clock divider & settings configuration
- * - For Linux: The old way of setting SPI speeds using BCM2835 driver enums has been removed as of v1.3.7
+ * @warning You MUST use begin(RF24_hal*)
*/
- RF24(uint32_t _spi_speed = RF24_SPI_SPEED);
+ RF24(void);
#if defined(RF24_LINUX)
virtual ~RF24() {};
@@ -243,58 +192,16 @@ public:
*/
bool begin(void);
-#if defined(RF24_SPI_PTR) || defined(DOXYGEN_FORCED)
/**
* Same as begin(), but allows specifying a non-default SPI bus to use.
*
- * @note This function assumes the `SPI::begin()` method was called before to
- * calling this function.
- *
- * @warning This function is for the Arduino platforms only
- *
- * @param spiBus A pointer or reference to an instantiated SPI bus object.
- * The `_SPI` datatype is a "wrapped" definition that will represent
- * various SPI implementations based on the specified platform.
- * @see Review the [Arduino support page](md_docs_arduino.html).
- *
- * @return same result as begin()
- */
- bool begin(_SPI* spiBus);
-
- /**
- * Same as begin(), but allows dynamically specifying a SPI bus, CE pin,
- * and CSN pin to use.
- *
- * @note This function assumes the `SPI::begin()` method was called before to
- * calling this function.
- *
* @warning This function is for the Arduino platforms only
*
- * @param spiBus A pointer or reference to an instantiated SPI bus object.
- * The `_SPI` datatype is a "wrapped" definition that will represent
- * various SPI implementations based on the specified platform.
- * @param _cepin The pin attached to Chip Enable on the RF module
- * @param _cspin The pin attached to Chip Select (often labeled CSN) on the radio module.
- * - For the Arduino Due board, the [Arduino Due extended SPI feature](https://www.arduino.cc/en/Reference/DueExtendedSPI)
- * is not supported. This means that the Due's pins 4, 10, or 52 are not mandated options (can use any digital output pin) for the radio's CSN pin.
+ * @param _hal A pointer to the device specific hardware abstraction layer
*
- * @see Review the [Arduino support page](md_docs_arduino.html).
- *
- * @return same result as begin()
- */
- bool begin(_SPI* spiBus, rf24_gpio_pin_t _cepin, rf24_gpio_pin_t _cspin);
-#endif // defined (RF24_SPI_PTR) || defined (DOXYGEN_FORCED)
-
- /**
- * Same as begin(), but allows dynamically specifying a CE pin
- * and CSN pin to use.
- * @param _cepin The pin attached to Chip Enable on the RF module
- * @param _cspin The pin attached to Chip Select (often labeled CSN) on the radio module.
- * - For the Arduino Due board, the [Arduino Due extended SPI feature](https://www.arduino.cc/en/Reference/DueExtendedSPI)
- * is not supported. This means that the Due's pins 4, 10, or 52 are not mandated options (can use any digital output pin) for the radio's CSN pin.
* @return same result as begin()
*/
- bool begin(rf24_gpio_pin_t _cepin, rf24_gpio_pin_t _cspin);
+ bool begin(RF24_hal* _hal);
/**
* Checks if the chip is connected to the SPI bus
@@ -667,12 +574,12 @@ public:
* This function uses much less ram than other `*print*Details()` methods.
*
* @code
- * uint8_t encoded_details[43] = {0};
+ * uint8_t encoded_details[38] = {0};
* radio.encodeRadioDetails(encoded_details);
* @endcode
*
* @param encoded_status The uint8_t array that RF24 radio details are
- * encoded into. This array must be at least 43 bytes in length; any less would surely
+ * encoded into. This array must be at least 38 bytes in length; any less would surely
* cause undefined behavior.
*
* Registers names and/or data corresponding to the index of the `encoded_details` array:
@@ -704,9 +611,6 @@ public:
* | 35 | FIFO_STATUS |
* | 36 | DYNPD |
* | 37 | FEATURE |
- * | 38-39 | ce_pin |
- * | 40-41 | csn_pin |
- * | 42 | SPI speed (in MHz) or'd with (isPlusVariant << 4) |
*/
void encodeRadioDetails(uint8_t* encoded_status);
@@ -1896,18 +1800,6 @@ private:
*/
bool _init_pins();
- /**
- * Set chip select pin
- *
- * Running SPI bus at PI_CLOCK_DIV2 so we don't waste time transferring data
- * and best of all, we make use of the radio's FIFO buffers. A lower speed
- * means we're less likely to effectively leverage our FIFOs and pay a higher
- * AVR runtime cost as toll.
- *
- * @param mode HIGH to take this unit off the SPI bus, LOW to put it on
- */
- void csn(bool mode);
-
/**
* Set chip enable
*
diff --git a/RF24_hal.cpp b/RF24_hal.cpp
new file mode 100644
index 0000000..3cc78e4
--- /dev/null
+++ b/RF24_hal.cpp
@@ -0,0 +1 @@
+#include "RF24_hal.h"
diff --git a/RF24_hal.h b/RF24_hal.h
new file mode 100644
index 0000000..baceab3
--- /dev/null
+++ b/RF24_hal.h
@@ -0,0 +1,15 @@
+#pragma once
+
+#include "RF24_config.h"
+
+class RF24_hal
+{
+public:
+ virtual void ce(bool level) = 0;
+ virtual uint8_t read(uint8_t cmd, uint8_t* buf, uint8_t len) = 0;
+ virtual uint8_t read(uint8_t cmd, uint8_t* buf, uint8_t data_len, uint8_t blank_len) = 0;
+ virtual uint8_t write(uint8_t cmd, const uint8_t* buf, uint8_t len) = 0;
+ virtual uint8_t write(uint8_t cmd, const uint8_t* buf, uint8_t len, uint8_t blank_len) = 0;
+ virtual bool begin() = 0;
+ virtual void end() = 0;
+};

3
scripts/applyPatches.py

@ -26,7 +26,10 @@ def applyPatch(libName, patchFile):
# list of patches to apply (relative to /src)
if env['PIOENV'][:22] != "opendtufusion-ethernet":
applyPatch("ESP Async WebServer", "../patches/AsyncWeb_Prometheus.patch")
if env['PIOENV'][:13] == "opendtufusion":
applyPatch("GxEPD2", "../patches/GxEPD2_SW_SPI.patch")
if env['PIOENV'][:22] == "opendtufusion-ethernet":
applyPatch("RF24", "../patches/RF24_Hal.patch")

13
scripts/getVersion.py

@ -55,6 +55,7 @@ def readVersion(path, infile):
os.mkdir(path + "firmware/ESP32/")
os.mkdir(path + "firmware/ESP32-S2/")
os.mkdir(path + "firmware/ESP32-S3/")
os.mkdir(path + "firmware/ESP32-S3-ETH/")
sha = os.getenv("SHA",default="sha")
versionout = version[:-1] + "_" + sha + "_esp8266.bin"
@ -98,6 +99,11 @@ def readVersion(path, infile):
dst = path + "firmware/ESP32-S3/" + versionout
os.rename(src, dst)
versionout = version[:-1] + "_" + sha + "_esp32s3_ethernet.bin"
src = path + ".pio/build/opendtufusion-ethernet/firmware.bin"
dst = path + "firmware/ESP32-S3-ETH/" + versionout
os.rename(src, dst)
# other ESP32 bin files
src = path + ".pio/build/esp32-wroom32/"
dst = path + "firmware/ESP32/"
@ -119,6 +125,13 @@ def readVersion(path, infile):
os.rename(src + "partitions.bin", dst + "partitions.bin")
genOtaBin(dst)
# other ESP32-S3-Eth bin files
src = path + ".pio/build/opendtufusion-ethernet/"
dst = path + "firmware/ESP32-S3-ETH/"
os.rename(src + "bootloader.bin", dst + "bootloader.bin")
os.rename(src + "partitions.bin", dst + "partitions.bin")
genOtaBin(dst)
os.rename("../scripts/gh-action-dev-build-flash.html", path + "install.html")
print("name=" + versionnumber[:-1] )

66
src/CHANGES.md

@ -1,5 +1,71 @@
# Development Changes
## 0.8.23 - 2023-12-14
* heuristics fix #1269 #1270
* moved `sendInterval` in settings, **important:** *will be reseted to 15s after update to this version*
* try to prevent access to radio classes if they are not activated
* fixed millis in serial log
* changed 'print whole trace' = `false` as default
* added communication loop duration in [ms] to serial console
* don't print Hex-Payload if 'print whole trace' == `false`
## 0.8.22 - 2023-12-13
* fix communication state-machine regarding zero export #1267
## 0.8.21 - 2023-12-12
* fix ethernet save inverter parameters #886
* fix ethernet OTA update #886
* improved radio statistics, fixed heuristic output for HMS and HMT inverters
## 0.8.20 - 2023-12-12
* improved HM communication #1259 #1249
* fix `loadDefaults` for ethernet builds #1263
* don't loop through radios which aren't in use #1264
## 0.8.19 - 2023-12-11
* added ms to serial log
* added (debug) option to configure gap between inverter requests
## 0.8.18 - 2023-12-10
* copied even more from the original heuristic code #1259
* added mDNS support #1262
## 0.8.17 - 2023-12-10
* possible fix of NRF with opendtufusion (without ETH)
* small fix in heuristics (if conditions made assignment not comparisson)
## 0.8.16 - 2023-12-09
* fix crash if NRF is not enabled
* updated heuristic #1080 #1259
* fix compile opendtufusion fusion ethernet
## 0.8.15 - 2023-12-09
* added support for opendtufusion fusion ethernet shield #886
* fixed range of HMS / HMT frequencies to 863 to 870 MHz #1238
* changed `yield effiency` per default to `1.0` #1243
* small heuristics improvements #1258
* added class to combine inverter heuristics fields #1258
## 0.8.14 - 2023-12-07
* fixed decimal points for temperature (WebUI) PR #1254 #1251
* fixed inverter statemachine available state PR #1252 #1253
* fixed NTP update and sunrise calculation #1240 #886
* display improvments #1248 #1247
* fixed overflow in `hmRadio.h` #1244
## 0.8.13 - 2023-11-28
* merge PR #1239 symbolic layout for OLED 128x64 + motion senser functionality
* fix MqTT IP addr for ETH connections PR #1240
* added ethernet build for fusion board, not tested so far
## 0.8.12 - 2023-11-20
* added button `copy to clipboard` to `/serial`
## 0.8.11 - 2023-11-20
* improved communication, thx @rejoe2
* improved heuristics, thx @rejoe2, @Oberfritze
* added option to strip payload of frames to significant area
## 0.8.10 - 2023-11-19
* fix Mi and HM inverter communication #1235
* added privacy mode option #1211

32
src/app.cpp

@ -18,7 +18,6 @@ void app::setup() {
while (!Serial)
yield();
resetSystem();
mSettings.setup();
@ -32,11 +31,11 @@ void app::setup() {
DBGPRINTLN(F("false"));
if(mConfig->nrf.enabled) {
mNrfRadio.setup(&mConfig->serial.debug, &mConfig->serial.privacyLog, mConfig->nrf.pinIrq, mConfig->nrf.pinCe, mConfig->nrf.pinCs, mConfig->nrf.pinSclk, mConfig->nrf.pinMosi, mConfig->nrf.pinMiso);
mNrfRadio.setup(&mConfig->serial.debug, &mConfig->serial.privacyLog, &mConfig->serial.printWholeTrace, mConfig->nrf.pinIrq, mConfig->nrf.pinCe, mConfig->nrf.pinCs, mConfig->nrf.pinSclk, mConfig->nrf.pinMosi, mConfig->nrf.pinMiso);
}
#if defined(ESP32)
if(mConfig->cmt.enabled) {
mCmtRadio.setup(&mConfig->serial.debug, &mConfig->serial.privacyLog, mConfig->cmt.pinSclk, mConfig->cmt.pinSdio, mConfig->cmt.pinCsb, mConfig->cmt.pinFcsb, false);
mCmtRadio.setup(&mConfig->serial.debug, &mConfig->serial.privacyLog, &mConfig->serial.printWholeTrace, mConfig->cmt.pinSclk, mConfig->cmt.pinSdio, mConfig->cmt.pinCsb, mConfig->cmt.pinFcsb, false);
}
#endif
#ifdef ETHERNET
@ -55,7 +54,7 @@ void app::setup() {
#endif
#endif /* defined(ETHERNET) */
mCommunication.setup(&mTimestamp, &mConfig->serial.debug, &mConfig->serial.privacyLog);
mCommunication.setup(&mTimestamp, &mConfig->serial.debug, &mConfig->serial.privacyLog, &mConfig->serial.printWholeTrace, &mConfig->inst.gapMs);
mCommunication.addPayloadListener(std::bind(&app::payloadEventListener, this, std::placeholders::_1, std::placeholders::_2));
mSys.setup(&mTimestamp, &mConfig->inst);
for (uint8_t i = 0; i < MAX_NUM_INVERTERS; i++) {
@ -86,7 +85,11 @@ void app::setup() {
// Plugins
#if defined(PLUGIN_DISPLAY)
if (mConfig->plugin.display.type != 0)
mDisplay.setup(this, &mConfig->plugin.display, &mSys, &mNrfRadio, &mTimestamp);
#if defined(ESP32)
mDisplay.setup(this, &mConfig->plugin.display, &mSys, &mNrfRadio, &mCmtRadio, &mTimestamp);
#else
mDisplay.setup(this, &mConfig->plugin.display, &mSys, &mNrfRadio, NULL, &mTimestamp);
#endif
#endif
mPubSerial.setup(mConfig, &mSys, &mTimestamp);
@ -107,8 +110,10 @@ void app::setup() {
void app::loop(void) {
ah::Scheduler::loop();
if(mConfig->nrf.enabled)
mNrfRadio.loop();
#if defined(ESP32)
if(mConfig->cmt.enabled)
mCmtRadio.loop();
#endif
mCommunication.loop();
@ -123,7 +128,7 @@ void app::onNetwork(bool gotIp) {
mNetworkConnected = gotIp;
ah::Scheduler::resetTicker();
regularTickers(); //reinstall regular tickers
every(std::bind(&app::tickSend, this), mConfig->nrf.sendInterval, "tSend");
every(std::bind(&app::tickSend, this), mConfig->inst.sendInterval, "tSend");
mMqttReconnect = true;
mSunrise = 0; // needs to be set to 0, to reinstall sunrise and ivComm tickers!
once(std::bind(&app::tickNtpUpdate, this), 2, "ntp2");
@ -209,7 +214,8 @@ void app::updateNtp(void) {
void app::tickNtpUpdate(void) {
uint32_t nxtTrig = 5; // default: check again in 5 sec
#if defined(ETHERNET)
bool isOK = mEth.updateNtpTime();
bool isOK = (mTimestamp != 0);
mEth.updateNtpTime();
#else
bool isOK = mWifi.getNtpTime();
#endif
@ -281,7 +287,7 @@ void app::tickIVCommunication(void) {
onceAt(std::bind(&app::tickIVCommunication, this), nxtTrig, "ivCom");
if (zeroValues) // at least one inverter
once(std::bind(&app::tickZeroValues, this), mConfig->nrf.sendInterval, "tZero");
once(std::bind(&app::tickZeroValues, this), mConfig->inst.sendInterval, "tZero");
}
//-----------------------------------------------------------------------------
@ -340,6 +346,16 @@ void app::tickMidnight(void) {
//-----------------------------------------------------------------------------
void app::tickSend(void) {
uint8_t fill = mCommunication.getFillState();
uint8_t max = mCommunication.getMaxFill();
if((max-MAX_NUM_INVERTERS) <= fill) {
DPRINT(DBG_WARN, F("send queue almost full, consider to increase interval, "));
DBGPRINT(String(fill));
DBGPRINT(F(" of "));
DBGPRINT(String(max));
DBGPRINTLN(F("entries used"));
}
for (uint8_t i = 0; i < MAX_NUM_INVERTERS; i++) {
Inverter<> *iv = mSys.getInverterByPos(i);
if(NULL == iv)

22
src/app.h

@ -14,7 +14,9 @@
#include "appInterface.h"
#include "hm/hmSystem.h"
#include "hm/hmRadio.h"
#if defined(ESP32)
#include "hms/hmsRadio.h"
#endif
#include "publisher/pubMqtt.h"
#include "publisher/pubSerial.h"
#include "utils/crc.h"
@ -40,7 +42,6 @@
typedef HmSystem<MAX_NUM_INVERTERS> HmSystemType;
#ifdef ESP32
typedef CmtRadio<esp32_3wSpi> CmtRadioType;
#endif
typedef Web<HmSystemType> WebType;
typedef RestApi<HmSystemType> RestApiType;
@ -51,7 +52,7 @@ typedef PubSerial<HmSystemType> PubSerialType;
#if defined(PLUGIN_DISPLAY)
#include "plugins/Display/Display.h"
#include "plugins/Display/Display_data.h"
typedef Display<HmSystemType, HmRadio<>> DisplayType;
typedef Display<HmSystemType, Radio> DisplayType;
#endif
#if defined(PLUGIN_ZEROEXPORT)
@ -95,7 +96,11 @@ class app : public IApp, public ah::Scheduler {
}
uint32_t getTimestamp() {
return Scheduler::getTimestamp();
return Scheduler::mTimestamp;
}
uint64_t getTimestampMs() {
return ((uint64_t)Scheduler::mTimestamp * 1000) + (uint64_t)Scheduler::mTsMillis;
}
bool saveSettings(bool reboot) {
@ -215,15 +220,6 @@ class app : public IApp, public ah::Scheduler {
return mConfig->cmt.pinIrq;
}
String getTimeStr(uint32_t offset = 0) {
char str[10];
if(0 == mTimestamp)
sprintf(str, "n/a");
else
sprintf(str, "%02d:%02d:%02d ", hour(mTimestamp + offset), minute(mTimestamp + offset), second(mTimestamp + offset));
return String(str);
}
uint32_t getTimezoneOffset() {
return mApi.getTimezoneOffset();
}
@ -331,7 +327,7 @@ class app : public IApp, public ah::Scheduler {
//Improv mImprov;
#endif
#ifdef ESP32
CmtRadioType mCmtRadio;
CmtRadio<> mCmtRadio;
#endif
char mVersion[12];

7
src/appInterface.h

@ -41,10 +41,10 @@ class IApp {
virtual uint32_t getUptime() = 0;
virtual uint32_t getTimestamp() = 0;
virtual uint64_t getTimestampMs() = 0;
virtual uint32_t getSunrise() = 0;
virtual uint32_t getSunset() = 0;
virtual void setTimestamp(uint32_t newTime) = 0;
virtual String getTimeStr(uint32_t offset) = 0;
virtual uint32_t getTimezoneOffset() = 0;
virtual void getSchedulerInfo(uint8_t *max) = 0;
virtual void getSchedulerNames() = 0;
@ -53,8 +53,11 @@ class IApp {
virtual bool getSettingsValid() = 0;
virtual void setMqttDiscoveryFlag() = 0;
virtual void setMqttPowerLimitAck(Inverter<> *iv) = 0;
virtual bool getMqttIsConnected() = 0;
virtual bool getNrfEnabled() = 0;
virtual bool getCmtEnabled() = 0;
virtual uint32_t getMqttRxCnt() = 0;
virtual uint32_t getMqttTxCnt() = 0;

26
src/config/config.h

@ -41,11 +41,21 @@
#if defined(ETHERNET)
#define ETH_SPI_HOST SPI2_HOST
#define ETH_SPI_CLOCK_MHZ 25
#define ETH_INT_GPIO 4
#define ETH_MISO_GPIO 12
#define ETH_MOSI_GPIO 13
#define ETH_SCK_GPIO 14
#define ETH_CS_PIN 15
#ifndef DEF_ETH_IRQ_PIN
#define DEF_ETH_IRQ_PIN 4
#endif
#ifndef DEF_ETH_MISO_PIN
#define DEF_ETH_MISO_PIN 12
#endif
#ifndef DEF_ETH_MOSI_PIN
#define DEF_ETH_MOSI_PIN 13
#endif
#ifndef DEF_ETH_SCK_PIN
#define DEF_ETH_SCK_PIN 14
#endif
#ifndef DEF_ETH_CS_PIN
#define DEF_ETH_CS_PIN 15
#endif
#else /* defined(ETHERNET) */
// time in seconds how long the station info (ssid + pwd) will be tried
#define WIFI_TRY_CONNECT_TIME 30
@ -98,6 +108,9 @@
#ifndef DEF_CMT_IRQ
#define DEF_CMT_IRQ 34
#endif
#ifndef DEF_MOTION_SENSOR_PIN
#define DEF_MOTION_SENSOR_PIN DEF_PIN_OFF
#endif
#else
#ifndef DEF_NRF_CS_PIN
#define DEF_NRF_CS_PIN 15
@ -119,6 +132,9 @@
#ifndef DEF_NRF_SCLK_PIN
#define DEF_NRF_SCLK_PIN 14
#endif
#ifndef DEF_MOTION_SENSOR_PIN
#define DEF_MOTION_SENSOR_PIN A0
#endif
#endif
#ifndef DEF_LED0
#define DEF_LED0 DEF_PIN_OFF

54
src/config/settings.h

@ -30,7 +30,7 @@
* https://arduino-esp8266.readthedocs.io/en/latest/filesystem.html#flash-layout
* */
#define CONFIG_VERSION 2
#define CONFIG_VERSION 5
#define PROT_MASK_INDEX 0x0001
@ -67,23 +67,19 @@ typedef struct {
bool darkMode;
bool schedReboot;
#if defined(ETHERNET)
// ethernet
#else /* defined(ETHERNET) */
#if !defined(ETHERNET)
// wifi
char stationSsid[SSID_LEN];
char stationPwd[PWD_LEN];
char apPwd[PWD_LEN];
bool isHidden;
#endif /* defined(ETHERNET) */
#endif /* !defined(ETHERNET) */
cfgIp_t ip;
} cfgSys_t;
typedef struct {
bool enabled;
uint16_t sendInterval;
uint8_t pinCs;
uint8_t pinCe;
uint8_t pinIrq;
@ -117,6 +113,7 @@ typedef struct {
bool showIv;
bool debug;
bool privacyLog;
bool printWholeTrace;
} cfgSerial_t;
typedef struct {
@ -170,18 +167,20 @@ typedef struct {
bool enabled;
cfgIv_t iv[MAX_NUM_INVERTERS];
uint16_t sendInterval;
bool rstYieldMidNight;
bool rstValsNotAvail;
bool rstValsCommStop;
bool rstMaxValsMidNight;
bool startWithoutTime;
float yieldEffiency;
uint16_t gapMs;
} cfgInst_t;
typedef struct {
uint8_t type;
bool pwrSaveAtIvOffline;
bool pxShift;
uint8_t screenSaver;
uint8_t rot;
//uint16_t wakeUp;
//uint16_t sleepAt;
@ -192,6 +191,7 @@ typedef struct {
uint8_t disp_reset;
uint8_t disp_busy;
uint8_t disp_dc;
uint8_t pirPin;
} display_t;
typedef struct {
@ -399,22 +399,19 @@ class settings {
mCfg.sys.darkMode = false;
mCfg.sys.schedReboot = false;
// restore temp settings
#if defined(ETHERNET)
memcpy(&mCfg.sys, &tmp, sizeof(cfgSys_t));
#else /* defined(ETHERNET) */
if(keepWifi)
memcpy(&mCfg.sys, &tmp, sizeof(cfgSys_t));
#if !defined(ETHERNET)
else {
snprintf(mCfg.sys.stationSsid, SSID_LEN, FB_WIFI_SSID);
snprintf(mCfg.sys.stationPwd, PWD_LEN, FB_WIFI_PWD);
snprintf(mCfg.sys.apPwd, PWD_LEN, WIFI_AP_PWD);
mCfg.sys.isHidden = false;
}
#endif /* defined(ETHERNET) */
#endif /* !defined(ETHERNET) */
snprintf(mCfg.sys.deviceName, DEVNAME_LEN, DEF_DEVICE_NAME);
mCfg.nrf.sendInterval = SEND_INTERVAL;
mCfg.nrf.pinCs = DEF_NRF_CS_PIN;
mCfg.nrf.pinCe = DEF_NRF_CE_PIN;
mCfg.nrf.pinIrq = DEF_NRF_IRQ_PIN;
@ -450,6 +447,7 @@ class settings {
mCfg.serial.showIv = false;
mCfg.serial.debug = false;
mCfg.serial.privacyLog = true;
mCfg.serial.printWholeTrace = true;
mCfg.mqtt.port = DEF_MQTT_PORT;
snprintf(mCfg.mqtt.broker, MQTT_ADDR_LEN, "%s", DEF_MQTT_BROKER);
@ -479,7 +477,8 @@ class settings {
mCfg.inst.rstValsCommStop = false;
mCfg.inst.startWithoutTime = false;
mCfg.inst.rstMaxValsMidNight = false;
mCfg.inst.yieldEffiency = 0.955f;
mCfg.inst.yieldEffiency = 1.0f;
mCfg.inst.gapMs = 2000;
for(uint8_t i = 0; i < MAX_NUM_INVERTERS; i++) {
mCfg.inst.iv[i].powerLevel = 0xff; // impossible high value
@ -496,7 +495,7 @@ class settings {
mCfg.plugin.display.pwrSaveAtIvOffline = false;
mCfg.plugin.display.contrast = 60;
mCfg.plugin.display.pxShift = true;
mCfg.plugin.display.screenSaver = 1; // default: 1 .. pixelshift for OLED for downward compatibility
mCfg.plugin.display.rot = 0;
mCfg.plugin.display.disp_data = DEF_PIN_OFF; // SDA
mCfg.plugin.display.disp_clk = DEF_PIN_OFF; // SCL
@ -504,6 +503,7 @@ class settings {
mCfg.plugin.display.disp_reset = DEF_PIN_OFF;
mCfg.plugin.display.disp_busy = DEF_PIN_OFF;
mCfg.plugin.display.disp_dc = DEF_PIN_OFF;
mCfg.plugin.display.pirPin = DEF_MOTION_SENSOR_PIN;
}
void loadAddedDefaults() {
@ -516,6 +516,16 @@ class settings {
mCfg.inst.iv[i].disNightCom = false;
mCfg.inst.iv[i].add2Total = true;
}
if(mCfg.configVersion < 3) {
mCfg.serial.printWholeTrace = false;
}
if(mCfg.configVersion < 4) {
mCfg.inst.gapMs = 2000;
}
if(mCfg.configVersion < 5) {
mCfg.inst.sendInterval = SEND_INTERVAL;
mCfg.serial.printWholeTrace = false;
}
}
}
@ -573,7 +583,6 @@ class settings {
void jsonNrf(JsonObject obj, bool set = false) {
if(set) {
obj[F("intvl")] = mCfg.nrf.sendInterval;
obj[F("cs")] = mCfg.nrf.pinCs;
obj[F("ce")] = mCfg.nrf.pinCe;
obj[F("irq")] = mCfg.nrf.pinIrq;
@ -582,7 +591,6 @@ class settings {
obj[F("miso")] = mCfg.nrf.pinMiso;
obj[F("en")] = (bool) mCfg.nrf.enabled;
} else {
getVal<uint16_t>(obj, F("intvl"), &mCfg.nrf.sendInterval);
getVal<uint8_t>(obj, F("cs"), &mCfg.nrf.pinCs);
getVal<uint8_t>(obj, F("ce"), &mCfg.nrf.pinCe);
getVal<uint8_t>(obj, F("irq"), &mCfg.nrf.pinIrq);
@ -661,10 +669,12 @@ class settings {
obj[F("show")] = mCfg.serial.showIv;
obj[F("debug")] = mCfg.serial.debug;
obj[F("prv")] = (bool) mCfg.serial.privacyLog;
obj[F("trc")] = (bool) mCfg.serial.printWholeTrace;
} else {
getVal<bool>(obj, F("show"), &mCfg.serial.showIv);
getVal<bool>(obj, F("debug"), &mCfg.serial.debug);
getVal<bool>(obj, F("prv"), &mCfg.serial.privacyLog);
getVal<bool>(obj, F("trc"), &mCfg.serial.printWholeTrace);
}
}
@ -740,7 +750,7 @@ class settings {
JsonObject disp = obj.createNestedObject("disp");
disp[F("type")] = mCfg.plugin.display.type;
disp[F("pwrSafe")] = (bool)mCfg.plugin.display.pwrSaveAtIvOffline;
disp[F("pxShift")] = (bool)mCfg.plugin.display.pxShift;
disp[F("screenSaver")] = mCfg.plugin.display.screenSaver;
disp[F("rotation")] = mCfg.plugin.display.rot;
//disp[F("wake")] = mCfg.plugin.display.wakeUp;
//disp[F("sleep")] = mCfg.plugin.display.sleepAt;
@ -751,11 +761,12 @@ class settings {
disp[F("reset")] = mCfg.plugin.display.disp_reset;
disp[F("busy")] = mCfg.plugin.display.disp_busy;
disp[F("dc")] = mCfg.plugin.display.disp_dc;
disp[F("pirPin")] = mCfg.plugin.display.pirPin;
} else {
JsonObject disp = obj["disp"];
getVal<uint8_t>(disp, F("type"), &mCfg.plugin.display.type);
getVal<bool>(disp, F("pwrSafe"), &mCfg.plugin.display.pwrSaveAtIvOffline);
getVal<bool>(disp, F("pxShift"), &mCfg.plugin.display.pxShift);
getVal<uint8_t>(disp, F("screenSaver"), &mCfg.plugin.display.screenSaver);
getVal<uint8_t>(disp, F("rotation"), &mCfg.plugin.display.rot);
//mCfg.plugin.display.wakeUp = disp[F("wake")];
//mCfg.plugin.display.sleepAt = disp[F("sleep")];
@ -766,11 +777,13 @@ class settings {
getVal<uint8_t>(disp, F("reset"), &mCfg.plugin.display.disp_reset);
getVal<uint8_t>(disp, F("busy"), &mCfg.plugin.display.disp_busy);
getVal<uint8_t>(disp, F("dc"), &mCfg.plugin.display.disp_dc);
getVal<uint8_t>(disp, F("pirPin"), &mCfg.plugin.display.pirPin);
}
}
void jsonInst(JsonObject obj, bool set = false) {
if(set) {
obj[F("intvl")] = mCfg.inst.sendInterval;
obj[F("en")] = (bool)mCfg.inst.enabled;
obj[F("rstMidNight")] = (bool)mCfg.inst.rstYieldMidNight;
obj[F("rstNotAvail")] = (bool)mCfg.inst.rstValsNotAvail;
@ -778,8 +791,10 @@ class settings {
obj[F("strtWthtTime")] = (bool)mCfg.inst.startWithoutTime;
obj[F("rstMaxMidNight")] = (bool)mCfg.inst.rstMaxValsMidNight;
obj[F("yldEff")] = mCfg.inst.yieldEffiency;
obj[F("gap")] = mCfg.inst.gapMs;
}
else {
getVal<uint16_t>(obj, F("intvl"), &mCfg.inst.sendInterval);
getVal<bool>(obj, F("en"), &mCfg.inst.enabled);
getVal<bool>(obj, F("rstMidNight"), &mCfg.inst.rstYieldMidNight);
getVal<bool>(obj, F("rstNotAvail"), &mCfg.inst.rstValsNotAvail);
@ -787,6 +802,7 @@ class settings {
getVal<bool>(obj, F("strtWthtTime"), &mCfg.inst.startWithoutTime);
getVal<bool>(obj, F("rstMaxMidNight"), &mCfg.inst.rstMaxValsMidNight);
getVal<float>(obj, F("yldEff"), &mCfg.inst.yieldEffiency);
getVal<uint16_t>(obj, F("gap"), &mCfg.inst.gapMs);
if(mCfg.inst.yieldEffiency < 0.5)
mCfg.inst.yieldEffiency = 1.0f;

2
src/defines.h

@ -13,7 +13,7 @@
//-------------------------------------
#define VERSION_MAJOR 0
#define VERSION_MINOR 8
#define VERSION_PATCH 10
#define VERSION_PATCH 23
//-------------------------------------
typedef struct {

56
src/eth/ahoyeth.cpp

@ -10,7 +10,7 @@
#define F(sl) (sl)
#endif
#include "ahoyeth.h"
#include <ESPmDNS.h>
//-----------------------------------------------------------------------------
ahoyeth::ahoyeth()
@ -41,8 +41,11 @@ void ahoyeth::setup(settings_t *config, uint32_t *utcTimestamp, OnNetworkCB onNe
if(!ETH.config(ip, gateway, mask, dns1, dns2))
DPRINTLN(DBG_ERROR, F("failed to set static IP!"));
}
ETH.begin(ETH_MISO_GPIO, ETH_MOSI_GPIO, ETH_SCK_GPIO, ETH_CS_PIN, ETH_INT_GPIO, ETH_SPI_CLOCK_MHZ, ETH_SPI_HOST);
#if defined(CONFIG_IDF_TARGET_ESP32S3)
mEthSpi.begin(DEF_ETH_MISO_PIN, DEF_ETH_MOSI_PIN, DEF_ETH_SCK_PIN, DEF_ETH_CS_PIN, DEF_ETH_IRQ_PIN, DEF_ETH_RST_PIN);
#else
ETH.begin(DEF_ETH_MISO_PIN, DEF_ETH_MOSI_PIN, DEF_ETH_SCK_PIN, DEF_ETH_CS_PIN, DEF_ETH_IRQ_PIN, ETH_SPI_CLOCK_MHZ, ETH_SPI_HOST);
#endif
}
@ -57,8 +60,7 @@ bool ahoyeth::updateNtpTime(void) {
return false;
DPRINTLN(DBG_DEBUG, F("updateNtpTime: checking udp \"connection\"...")); Serial.flush();
if (!mUdp.connected())
{
if (!mUdp.connected()) {
DPRINTLN(DBG_DEBUG, F("updateNtpTime: About to (re)connect...")); Serial.flush();
IPAddress timeServer;
if (!WiFi.hostByName(mConfig->ntp.addr, timeServer))
@ -68,8 +70,7 @@ bool ahoyeth::updateNtpTime(void) {
return false;
DPRINTLN(DBG_DEBUG, F("updateNtpTime: Connected...")); Serial.flush();
mUdp.onPacket([this](AsyncUDPPacket packet)
{
mUdp.onPacket([this](AsyncUDPPacket packet) {
DPRINTLN(DBG_DEBUG, F("updateNtpTime: about to handle ntp packet...")); Serial.flush();
this->handleNTPPacket(packet);
});
@ -132,8 +133,7 @@ void ahoyeth::welcome(String ip, String mode) {
void ahoyeth::onEthernetEvent(WiFiEvent_t event, arduino_event_info_t info)
{
AWS_LOG(F("[ETH]: Got event..."));
switch (event)
{
switch (event) {
#if ( ( defined(ESP_ARDUINO_VERSION_MAJOR) && (ESP_ARDUINO_VERSION_MAJOR >= 2) ) && ( ARDUINO_ESP32_GIT_VER != 0x46d5afb1 ) )
// For breaking core v2.0.0
// Why so strange to define a breaking enum arduino_event_id_t in WiFiGeneric.h
@ -153,16 +153,16 @@ void ahoyeth::onEthernetEvent(WiFiEvent_t event, arduino_event_info_t info)
break;
case ARDUINO_EVENT_ETH_GOT_IP:
if (!ESP32_W5500_eth_connected)
{
if (!ESP32_W5500_eth_connected) {
#if defined (CONFIG_IDF_TARGET_ESP32S3)
AWS_LOG3(F("ETH MAC: "), mEthSpi.macAddress(), F(", IPv4: "), ETH.localIP());
#else
AWS_LOG3(F("ETH MAC: "), ETH.macAddress(), F(", IPv4: "), ETH.localIP());
#endif
if (ETH.fullDuplex())
{
if (ETH.fullDuplex()) {
AWS_LOG0(F("FULL_DUPLEX, "));
}
else
{
} else {
AWS_LOG0(F("HALF_DUPLEX, "));
}
@ -171,6 +171,13 @@ void ahoyeth::onEthernetEvent(WiFiEvent_t event, arduino_event_info_t info)
ESP32_W5500_eth_connected = true;
mOnNetworkCB(true);
}
if (!MDNS.begin(mConfig->sys.deviceName)) {
DPRINTLN(DBG_ERROR, F("Error setting up MDNS responder!"));
} else {
DBGPRINT(F("[WiFi] mDNS established: "));
DBGPRINT(mConfig->sys.deviceName);
DBGPRINTLN(F(".local"));
}
break;
case ARDUINO_EVENT_ETH_DISCONNECTED:
@ -208,16 +215,12 @@ void ahoyeth::onEthernetEvent(WiFiEvent_t event, arduino_event_info_t info)
break;
case SYSTEM_EVENT_ETH_GOT_IP:
if (!ESP32_W5500_eth_connected)
{
if (!ESP32_W5500_eth_connected) {
AWS_LOG3(F("ETH MAC: "), ETH.macAddress(), F(", IPv4: "), ETH.localIP());
if (ETH.fullDuplex())
{
if (ETH.fullDuplex()) {
AWS_LOG0(F("FULL_DUPLEX, "));
}
else
{
} else {
AWS_LOG0(F("HALF_DUPLEX, "));
}
@ -226,6 +229,13 @@ void ahoyeth::onEthernetEvent(WiFiEvent_t event, arduino_event_info_t info)
ESP32_W5500_eth_connected = true;
mOnNetworkCB(true);
}
if (!MDNS.begin(mConfig->sys.deviceName)) {
DPRINTLN(DBG_ERROR, F("Error setting up MDNS responder!"));
} else {
DBGPRINT(F("[WiFi] mDNS established: "));
DBGPRINT(mConfig->sys.deviceName);
DBGPRINTLN(F(".local"));
}
break;
case SYSTEM_EVENT_ETH_DISCONNECTED:

4
src/eth/ahoyeth.h

@ -13,6 +13,7 @@
#include <AsyncUDP.h>
#include <DNSServer.h>
#include "ethSpi.h"
#include "../utils/dbg.h"
#include "../config/config.h"
#include "../config/settings.h"
@ -45,6 +46,9 @@ class ahoyeth {
void onEthernetEvent(WiFiEvent_t event, arduino_event_info_t info);
private:
#if defined(CONFIG_IDF_TARGET_ESP32S3)
EthSpi mEthSpi;
#endif
settings_t *mConfig;
uint32_t *mUtcTimestamp;

141
src/eth/ethSpi.h

@ -0,0 +1,141 @@
//-----------------------------------------------------------------------------
// 2023 Ahoy, https://www.mikrocontroller.net/topic/525778
// Creative Commons - http://creativecommons.org/licenses/by-nc-sa/3.0/de/
//-----------------------------------------------------------------------------
#if defined(CONFIG_IDF_TARGET_ESP32S3)
#if defined(ETHERNET)
#ifndef __ETH_SPI_H__
#define __ETH_SPI_H__
#pragma once
#include <Arduino.h>
#include <esp_netif.h>
#include <WiFiGeneric.h>
#include <driver/spi_master.h>
// Functions from WiFiGeneric
void tcpipInit();
void add_esp_interface_netif(esp_interface_t interface, esp_netif_t* esp_netif);
class EthSpi {
public:
EthSpi() :
eth_handle(nullptr),
eth_netif(nullptr) {}
void begin(int8_t pin_miso, int8_t pin_mosi, int8_t pin_sclk, int8_t pin_cs, int8_t pin_int, int8_t pin_rst) {
gpio_reset_pin(static_cast<gpio_num_t>(pin_rst));
gpio_set_direction(static_cast<gpio_num_t>(pin_rst), GPIO_MODE_OUTPUT);
gpio_set_level(static_cast<gpio_num_t>(pin_rst), 0);
gpio_reset_pin(static_cast<gpio_num_t>(pin_sclk));
gpio_reset_pin(static_cast<gpio_num_t>(pin_mosi));
gpio_reset_pin(static_cast<gpio_num_t>(pin_miso));
gpio_reset_pin(static_cast<gpio_num_t>(pin_cs));
gpio_set_pull_mode(static_cast<gpio_num_t>(pin_miso), GPIO_PULLUP_ONLY);
// Workaround, because calling gpio_install_isr_service directly causes issues with attachInterrupt later
attachInterrupt(digitalPinToInterrupt(pin_int), nullptr, CHANGE);
detachInterrupt(digitalPinToInterrupt(pin_int));
gpio_reset_pin(static_cast<gpio_num_t>(pin_int));
gpio_set_pull_mode(static_cast<gpio_num_t>(pin_int), GPIO_PULLUP_ONLY);
spi_bus_config_t buscfg = {
.mosi_io_num = pin_mosi,
.miso_io_num = pin_miso,
.sclk_io_num = pin_sclk,
.quadwp_io_num = -1,
.quadhd_io_num = -1,
.data4_io_num = -1,
.data5_io_num = -1,
.data6_io_num = -1,
.data7_io_num = -1,
.max_transfer_sz = 0, // uses default value internally
.flags = 0,
.intr_flags = 0
};
ESP_ERROR_CHECK(spi_bus_initialize(SPI3_HOST, &buscfg, SPI_DMA_CH_AUTO));
spi_device_interface_config_t devcfg = {
.command_bits = 16, // actually address phase
.address_bits = 8, // actually command phase
.dummy_bits = 0,
.mode = 0,
.duty_cycle_pos = 0,
.cs_ena_pretrans = 0, // only 0 supported
.cs_ena_posttrans = 0, // only 0 supported
.clock_speed_hz = 20000000, // stable with on OpenDTU Fusion Shield
.input_delay_ns = 0,
.spics_io_num = pin_cs,
.flags = 0,
.queue_size = 20,
.pre_cb = nullptr,
.post_cb = nullptr
};
spi_device_handle_t spi;
ESP_ERROR_CHECK(spi_bus_add_device(SPI3_HOST, &devcfg, &spi));
// Reset sequence
delayMicroseconds(500);
gpio_set_level(static_cast<gpio_num_t>(pin_rst), 1);
delayMicroseconds(1000);
// Arduino function to start networking stack if not already started
tcpipInit();
ESP_ERROR_CHECK(tcpip_adapter_set_default_eth_handlers()); // ?
eth_w5500_config_t w5500_config = ETH_W5500_DEFAULT_CONFIG(spi);
w5500_config.int_gpio_num = pin_int;
eth_mac_config_t mac_config = ETH_MAC_DEFAULT_CONFIG();
mac_config.rx_task_stack_size = 4096;
esp_eth_mac_t *mac = esp_eth_mac_new_w5500(&w5500_config, &mac_config);
eth_phy_config_t phy_config = ETH_PHY_DEFAULT_CONFIG();
phy_config.reset_gpio_num = -1;
esp_eth_phy_t *phy = esp_eth_phy_new_w5500(&phy_config);
esp_eth_config_t eth_config = ETH_DEFAULT_CONFIG(mac, phy);
ESP_ERROR_CHECK(esp_eth_driver_install(&eth_config, &eth_handle));
// Configure MAC address
uint8_t mac_addr[6];
ESP_ERROR_CHECK(esp_efuse_mac_get_default(mac_addr));
mac_addr[5] |= 0x03; // derive ethernet MAC address from base MAC address
ESP_ERROR_CHECK(esp_eth_ioctl(eth_handle, ETH_CMD_S_MAC_ADDR, mac_addr));
esp_netif_config_t netif_config = ESP_NETIF_DEFAULT_ETH();
eth_netif = esp_netif_new(&netif_config);
ESP_ERROR_CHECK(esp_netif_attach(eth_netif, esp_eth_new_netif_glue(eth_handle)));
// Add to Arduino
add_esp_interface_netif(ESP_IF_ETH, eth_netif);
ESP_ERROR_CHECK(esp_eth_start(eth_handle));
}
String macAddress() {
uint8_t mac_addr[6] = {0, 0, 0, 0, 0, 0};
esp_eth_ioctl(eth_handle, ETH_CMD_G_MAC_ADDR, mac_addr);
char mac_addr_str[24];
snprintf(mac_addr_str, sizeof(mac_addr_str), "%02X:%02X:%02X:%02X:%02X:%02X", mac_addr[0], mac_addr[1], mac_addr[2], mac_addr[3], mac_addr[4], mac_addr[5]);
return String(mac_addr_str);
}
private:
esp_eth_handle_t eth_handle;
esp_netif_t *eth_netif;
};
#endif /*__ETH_SPI_H__*/
#endif /*ETHERNET*/
#endif /*CONFIG_IDF_TARGET_ESP32S3*/

9
src/hm/CommQueue.h

@ -9,6 +9,7 @@
#include <array>
#include <functional>
#include "hmInverter.h"
#include "../utils/dbg.h"
template <uint8_t N=100>
class CommQueue {
@ -29,6 +30,14 @@ class CommQueue {
mQueue[mWrPtr] = queue_s(iv, cmd, delOnPop, false);
}
uint8_t getFillState(void) {
return abs(mRdPtr - mWrPtr);
}
uint8_t getMaxFill(void) {
return N;
}
protected:
struct queue_s {
Inverter<> *iv;

370
src/hm/Communication.h

@ -22,10 +22,12 @@ typedef std::function<void(Inverter<> *)> alarmListenerType;
class Communication : public CommQueue<> {
public:
void setup(uint32_t *timestamp, bool *serialDebug, bool *privacyMode) {
void setup(uint32_t *timestamp, bool *serialDebug, bool *privacyMode, bool *printWholeTrace, uint16_t *inverterGap) {
mTimestamp = timestamp;
mPrivacyMode = privacyMode;
mSerialDebug = serialDebug;
mPrintWholeTrace = printWholeTrace;
mInverterGap = inverterGap;
}
void addImportant(Inverter<> *iv, uint8_t cmd, bool delOnPop = true) {
@ -43,13 +45,28 @@ class Communication : public CommQueue<> {
void loop() {
get([this](bool valid, const queue_s *q) {
if(!valid)
if(!valid) {
if(mPrintSequenceDuration) {
mPrintSequenceDuration = false;
DPRINT(DBG_INFO, F("com loop duration: "));
DBGPRINT(String(millis() - mLastEmptyQueueMillis));
DBGPRINTLN(F("ms"));
DBGPRINTLN(F("-----"));
}
return; // empty
}
if(!mPrintSequenceDuration) // entry was added to the queue
mLastEmptyQueueMillis = millis();
mPrintSequenceDuration = true;
uint16_t timeout = q->iv->ivGen != IV_MI ? ((q->iv->mGotFragment && q->iv->mGotLastMsg) ? SINGLEFR_TIMEOUT : DEFAULT_TIMEOUT) : MI_TIMEOUT;
uint16_t timeout_min = q->iv->ivGen != IV_MI ? ((q->iv->mGotFragment) ? SINGLEFR_TIMEOUT : FRSTMSG_TIMEOUT) : MI_TIMEOUT;
bool testMode = false;
uint16_t timeout = (q->iv->ivGen == IV_MI) ? MI_TIMEOUT : ((q->iv->mGotFragment && q->iv->mGotLastMsg) || mIsRetransmit) ? SINGLEFR_TIMEOUT : DEFAULT_TIMEOUT;
uint16_t timeout_min = (q->iv->ivGen == IV_MI) ? MI_TIMEOUT : ((q->iv->mGotFragment || mIsRetransmit)) ? SINGLEFR_TIMEOUT : FRSTMSG_TIMEOUT;
/*if(mDebugState != mState) {
DPRINT(DBG_INFO, F("State: "));
DBGHEXLN((uint8_t)(mState));
mDebugState = mState;
}*/
switch(mState) {
case States::RESET:
if(millis() < mWaitTimeout)
@ -62,10 +79,10 @@ class Communication : public CommQueue<> {
if(*mSerialDebug)
mHeu.printStatus(q->iv);
mHeu.getTxCh(q->iv);
testMode = mHeu.getTestModeEnabled();
q->iv->mGotFragment = false;
q->iv->mGotLastMsg = false;
mFirstTry = mFirstTry ? false : (((IV_HM == q->iv->ivGen) || (IV_MI == q->iv->ivGen)) && ((q->iv->isAvailable()) || (millis() < 120000)));
q->iv->curFrmCnt = 0;
mIsRetransmit = false;
if(NULL == q->iv->radio)
cmdDone(true); // can't communicate while radio is not defined!
mState = States::START;
@ -87,118 +104,111 @@ class Communication : public CommQueue<> {
q->iv->radio->sendControlPacket(q->iv, q->cmd, q->iv->powerLimit, false);
} else
q->iv->radio->prepareDevInformCmd(q->iv, q->cmd, q->ts, q->iv->alarmLastId, false);
if(!testMode)
q->iv->radioStatistics.txCnt++;
mWaitTimeout = millis() + timeout;
mWaitTimeout_min = millis() + timeout_min;
mIsRetransmit = false;
mlastTO_min = timeout_min;
setAttempt();
mState = States::WAIT;
break;
case States::WAIT:
if(millis() > mWaitTimeout_min) {
if(!q->iv->mGotFragment) { // nothing received yet?
/*if(millis() > mWaitTimeout_min) {
if(mIsRetransmit) { // we already have been through...
mWaitTimeout = mWaitTimeout_min;
} else if(q->iv->mGotFragment) { // nothing received yet?
if(q->iv->mGotLastMsg) {
//mState = States::CHECK_FRAMES;
mWaitTimeout = mWaitTimeout_min;
}
} else if(mFirstTry) {
if(*mSerialDebug) {
DPRINT_IVID(DBG_INFO, q->iv->id);
DBGPRINTLN(F("second try"));
DBGPRINT(String(millis() - mWaitTimeout_min + mlastTO_min));
DBGPRINTLN(F("ms - second try"));
}
mFirstTry = false;
if(!testMode)
mlastTO_min = timeout_min;
q->iv->radioStatistics.retransmits++; // got nothing
mState = States::START;
break;
}
}
}*/
if(millis() < mWaitTimeout)
return;
mState = States::CHECK_FRAMES;
break;
case States::CHECK_FRAMES: {
if(!q->iv->radio->get()) { // radio buffer empty
cmdDone();
if((q->iv->radio->mBufCtrl.empty() && !mIsRetransmit) || (0 == q->attempts)) { // radio buffer empty or no more answers
if(*mSerialDebug) {
DPRINT_IVID(DBG_INFO, q->iv->id);
DBGPRINT(F("request timeout: "));
DBGPRINT(String(millis() - mWaitTimeout + timeout));
DBGPRINTLN(F("ms"));
}
if(!q->iv->mGotFragment) {
if(!testMode)
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, (q->iv->config->frequency*FREQ_STEP_KHZ + HOY_BASE_FREQ_KHZ));
mWaitTimeout = millis() + 1000;
}
} else {
if(!testMode)
q->iv->radioStatistics.rxFail++;
}
mState = States::RESET;
closeRequest(q, false);
break;
}
mIsRetransmit = false;
mFirstTry = false; // for correct reset
States nextState = States::RESET;
while(!q->iv->radio->mBufCtrl.empty()) {
packet_t *p = &q->iv->radio->mBufCtrl.front();
printRxInfo(q, p);
DPRINT_IVID(DBG_INFO, q->iv->id);
DBGPRINT(F("RX "));
if(p->millis < 100)
DBGPRINT(F(" "));
DBGPRINT(String(p->millis));
DBGPRINT(F("ms "));
DBGPRINT(String(p->len));
if((IV_HM == q->iv->ivGen) || (IV_MI == q->iv->ivGen)) {
DBGPRINT(F(" CH"));
if(3 == p->ch)
DBGPRINT(F("0"));
DBGPRINT(String(p->ch));
}
DBGPRINT(F(", "));
DBGPRINT(String(p->rssi));
DBGPRINT(F("dBm | "));
if(*mPrivacyMode)
ah::dumpBuf(p->packet, p->len, 1, 8);
else
ah::dumpBuf(p->packet, p->len);
if(checkIvSerial(&p->packet[1], q->iv)) {
if(!testMode)
if(validateIvSerial(&p->packet[1], q->iv)) {
q->iv->radioStatistics.frmCnt++;
if (p->packet[0] == (TX_REQ_INFO + ALL_FRAMES)) { // response from get information command
parseFrame(p);
nextState = States::CHECK_PACKAGE;
if(parseFrame(p))
q->iv->curFrmCnt++;
} else if (p->packet[0] == (TX_REQ_DEVCONTROL + ALL_FRAMES)) { // response from dev control command
parseDevCtrl(p, q);
cmdDone(true); // remove done request
if(parseDevCtrl(p, q))
closeRequest(q, true);
else
closeRequest(q, false);
return; // don't wait for empty buffer
} else if(IV_MI == q->iv->ivGen) {
parseMiFrame(p, q);
}
} else {
if(!testMode)
q->iv->radioStatistics.rxFail++; // got no complete payload
DPRINTLN(DBG_WARN, F("Inverter serial does not match"));
mWaitTimeout = millis() + timeout;
if(parseMiFrame(p, q))
q->iv->curFrmCnt++;
}
} //else // serial does not match
q->iv->radio->mBufCtrl.pop();
yield();
}
if(0 == q->attempts) {
if(!testMode)
q->iv->radioStatistics.rxFail++; // got no complete payload
mHeu.setGotFragment(q->iv);
cmdDone(true);
mState = States::RESET;
} else
mState = nextState;
DPRINT_IVID(DBG_INFO, q->iv->id);
DBGPRINT(F("no attempts left"));
closeRequest(q, false);
} else {
if(q->iv->ivGen != IV_MI) {
mState = States::CHECK_PACKAGE;
} else {
if(q->iv->miMultiParts < 6) {
mState = States::WAIT;
} else {
if(((q->cmd == 0x39) && (q->iv->type == INV_TYPE_4CH))
|| ((q->cmd == MI_REQ_CH2) && (q->iv->type == INV_TYPE_2CH))
|| ((q->cmd == MI_REQ_CH1) && (q->iv->type == INV_TYPE_1CH))) {
miComplete(q->iv);
}
closeRequest(q, true);
}
}
}
}
break;
@ -228,37 +238,75 @@ class Communication : public CommQueue<> {
if(framnr) {
setAttempt();
if(*mSerialDebug) {
DPRINT_IVID(DBG_WARN, q->iv->id);
DBGPRINT(F("frame "));
DBGPRINT(String(framnr));
DBGPRINT(F(" missing: request retransmit ("));
DBGPRINT(String(q->attempts));
DBGPRINTLN(F(" attempts left)"));
sendRetransmit(q, framnr-1);
}
sendRetransmit(q, (framnr-1));
mIsRetransmit = true;
mlastTO_min = timeout_min;
return;
}
mHeu.setGotAll(q->iv);
compilePayload(q, testMode);
compilePayload(q);
if(NULL != mCbPayload)
(mCbPayload)(q->cmd, q->iv);
cmdDone(true); // remove done request
mState = States::RESET; // everything ok, next request
closeRequest(q, true);
break;
}
});
}
private:
inline bool checkIvSerial(uint8_t buf[], Inverter<> *iv) {
inline void printRxInfo(const queue_s *q, packet_t *p) {
DPRINT_IVID(DBG_INFO, q->iv->id);
DBGPRINT(F("RX "));
if(p->millis < 100)
DBGPRINT(F(" "));
DBGPRINT(String(p->millis));
DBGPRINT(F("ms | "));
DBGPRINT(String(p->len));
if((IV_HM == q->iv->ivGen) || (IV_MI == q->iv->ivGen)) {
DBGPRINT(F(" CH"));
if(3 == p->ch)
DBGPRINT(F("0"));
DBGPRINT(String(p->ch));
DBGPRINT(F(" "));
} else {
DBGPRINT(F(" "));
DBGPRINT(String(p->rssi));
DBGPRINT(F("dBm | "));
}
if(*mPrintWholeTrace) {
if(*mPrivacyMode)
ah::dumpBuf(p->packet, p->len, 1, 8);
else
ah::dumpBuf(p->packet, p->len);
} else {
DBGPRINT(F("| "));
DBGHEXLN(p->packet[9]);
}
}
inline bool validateIvSerial(uint8_t buf[], Inverter<> *iv) {
uint8_t tmp[4];
CP_U32_BigEndian(tmp, iv->radioId.u64 >> 8);
for(uint8_t i = 0; i < 4; i++) {
if(tmp[i] != buf[i])
if(tmp[i] != buf[i]) {
DPRINT(DBG_WARN, F("Inverter serial does not match, got: 0x"));
DHEX(buf[0]);DHEX(buf[1]);DHEX(buf[2]);DHEX(buf[3]);
DBGPRINT(F(", expected: 0x"));
DHEX(tmp[0]);DHEX(tmp[1]);DHEX(tmp[2]);DHEX(tmp[3]);
DBGPRINTLN("");
return false;
}
}
return true;
}
@ -266,20 +314,20 @@ class Communication : public CommQueue<> {
return (ah::crc8(buf, len - 1) == buf[len-1]);
}
inline void parseFrame(packet_t *p) {
inline bool parseFrame(packet_t *p) {
uint8_t *frameId = &p->packet[9];
if(0x00 == *frameId) {
DPRINTLN(DBG_WARN, F("invalid frameId 0x00"));
return; // skip current packet
return false; // skip current packet
}
if((*frameId & 0x7f) > MAX_PAYLOAD_ENTRIES) {
DPRINTLN(DBG_WARN, F("local buffer to small for payload fragments"));
return; // local storage is to small for id
return false; // local storage is to small for id
}
if(!checkFrameCrc(p->packet, p->len)) {
DPRINTLN(DBG_WARN, F("frame CRC is wrong"));
return; // CRC8 is wrong, frame invalid
return false; // CRC8 is wrong, frame invalid
}
if((*frameId & ALL_FRAMES) == ALL_FRAMES)
@ -289,9 +337,11 @@ class Communication : public CommQueue<> {
memcpy(f->buf, &p->packet[10], p->len-11);
f->len = p->len - 11;
f->rssi = p->rssi;
return true;
}
inline void parseMiFrame(packet_t *p, const queue_s *q) {
inline bool parseMiFrame(packet_t *p, const queue_s *q) {
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))
@ -306,13 +356,15 @@ class Communication : public CommQueue<> {
record_t<> *rec = q->iv->getRecordStruct(RealTimeRunData_Debug); // choose the record structure
rec->ts = q->ts;
miStsConsolidate(q, ((p->packet[0] == 0x88) ? 1 : 2), rec, p->packet[10], p->packet[12], p->packet[9], p->packet[11]);
mHeu.setGotFragment(q->iv);
//mHeu.setGotFragment(q->iv); only do this when we are through the cycle?
}
return true;
}
inline void parseDevCtrl(packet_t *p, const queue_s *q) {
inline bool parseDevCtrl(packet_t *p, const queue_s *q) {
if((p->packet[12] != ActivePowerContr) || (p->packet[13] != 0x00))
return;
return false;
bool accepted = true;
if((p->packet[10] == 0x00) && (p->packet[11] == 0x00))
q->iv->powerLimitAck = true;
@ -327,9 +379,11 @@ class Communication : public CommQueue<> {
DBGPRINT(F(" with PowerLimitControl "));
DBGPRINTLN(String(q->iv->powerLimit[1]));
q->iv->actPowerLimit = 0xffff; // unknown, readback current value
return accepted;
}
inline void compilePayload(const queue_s *q, bool testMode) {
inline void compilePayload(const queue_s *q) {
uint16_t crc = 0xffff, crcRcv = 0x0000;
for(uint8_t i = 0; i < mMaxFrameId; i++) {
if(i == (mMaxFrameId - 1)) {
@ -345,9 +399,10 @@ class Communication : public CommQueue<> {
DBGPRINT(F("CRC Error "));
if(q->attempts == 0) {
DBGPRINTLN(F("-> Fail"));
if(!testMode)
q->iv->radioStatistics.rxFail++; // got fragments but not complete response
cmdDone();
/*q->iv->radioStatistics.rxFail++; // got fragments but not complete response
cmdDone();*/
closeRequest(q, false);
} else
DBGPRINTLN(F("-> complete retransmit"));
mState = States::RESET;
@ -379,8 +434,11 @@ class Communication : public CommQueue<> {
DPRINT_IVID(DBG_INFO, q->iv->id);
DBGPRINT(F("Payload ("));
DBGPRINT(String(len));
if(*mPrintWholeTrace) {
DBGPRINT(F("): "));
ah::dumpBuf(mPayload, len);
} else
DBGPRINTLN(F(")"));
record_t<> *rec = q->iv->getRecordStruct(q->cmd);
if(NULL == rec) {
@ -388,16 +446,16 @@ class Communication : public CommQueue<> {
return;
}
if((rec->pyldLen != len) && (0 != rec->pyldLen)) {
if(*mSerialDebug) {
DPRINT(DBG_ERROR, F("plausibility check failed, expected "));
DBGPRINT(String(rec->pyldLen));
DBGPRINTLN(F(" bytes"));
if(!testMode)
q->iv->radioStatistics.rxFail++;
return;
}
/*q->iv->radioStatistics.rxFail++;*/
closeRequest(q, false);
if(!testMode)
q->iv->radioStatistics.rxSuccess++;
return;
}
rec->ts = q->ts;
for (uint8_t i = 0; i < rec->length; i++) {
@ -426,15 +484,33 @@ class Communication : public CommQueue<> {
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;
//add(q, true);
closeRequest(q, false);
}
}
private:
void closeRequest(const queue_s *q, bool crcPass) {
mHeu.evalTxChQuality(q->iv, crcPass, (4 - q->attempts), q->iv->curFrmCnt);
if(crcPass)
q->iv->radioStatistics.rxSuccess++;
else if(q->iv->mGotFragment)
q->iv->radioStatistics.rxFail++; // got no complete payload
else {
q->iv->radioStatistics.rxFailNoAnser++; // got nothing
}
mWaitTimeout = millis() + *mInverterGap;
cmdDone(q->delOnPop);
q->iv->mGotFragment = false;
q->iv->mGotLastMsg = false;
q->iv->miMultiParts = 0;
mIsRetransmit = false;
mFirstTry = false; // for correct reset
mState = States::RESET;
DBGPRINTLN(F("-----"));
}
inline void miHwDecode(packet_t *p, const queue_s *q) {
record_t<> *rec = q->iv->getRecordStruct(InverterDevInform_All); // choose the record structure
rec->ts = q->ts;
@ -478,11 +554,11 @@ class Communication : public CommQueue<> {
q->iv->setValue(i, rec, (float) ((p->packet[(12+2*i)] << 8) + p->packet[(13+2*i)])/1);
}
q->iv->isConnected = true;
//if(mSerialDebug) {
if(*mSerialDebug) {
DPRINT_IVID(DBG_INFO, q->iv->id);
DBGPRINT(F("HW_VER is "));
DBGPRINTLN(String((p->packet[24] << 8) + p->packet[25]));
//}
}
record_t<> *rec = q->iv->getRecordStruct(InverterDevInform_Simple); // choose the record structure
rec->ts = q->ts;
q->iv->setValue(1, rec, (uint32_t) ((p->packet[24] << 8) + p->packet[25])/1);
@ -504,7 +580,7 @@ class Communication : public CommQueue<> {
rec->ts = q->ts;
q->iv->setValue(0, rec, (uint32_t) ((((p->packet[10] << 8) | p->packet[11]) << 8 | p->packet[12]) << 8 | p->packet[13])/1);
//if(mSerialDebug) {
if(*mSerialDebug) {
DPRINT(DBG_INFO,F("HW_FB_TLmValue "));
DBGPRINTLN(String((p->packet[14] << 8) + p->packet[15]));
DBGPRINT(F("HW_FB_ReSPRT "));
@ -515,7 +591,7 @@ class Communication : public CommQueue<> {
DBGPRINTLN(String((p->packet[20] << 8) + p->packet[21]));
DBGPRINT(F("Matching_APPFW_PN "));
DBGPRINTLN(String((uint32_t) (((p->packet[22] << 8) | p->packet[23]) << 8 | p->packet[24]) << 8 | p->packet[25]));
//}
}
if(NULL != mCbPayload)
(mCbPayload)(InverterDevInform_All, q->iv);
q->iv->miMultiParts +=2;
@ -533,28 +609,23 @@ class Communication : public CommQueue<> {
byte[15] byte[16] PNInfoCRC_gusv
byte[15] byte[16] PNInfoCRC_gusv (this really is double mentionned in xlsx...)
*/
//if(mSerialDebug) {
if(*mSerialDebug) {
DPRINT(DBG_INFO,F("APPFW_MINVER "));
DBGPRINTLN(String((p->packet[10] << 8) + p->packet[11]));
DBGPRINT(F("HWInfoAddr "));
DBGPRINTLN(String((p->packet[12] << 8) + p->packet[13]));
DBGPRINT(F("PNInfoCRC_gusv "));
DBGPRINTLN(String((p->packet[14] << 8) + p->packet[15]));
//}
}
if(NULL != mCbPayload)
(mCbPayload)(InverterDevInform_Simple, q->iv);
q->iv->miMultiParts++;
}
if(q->iv->miMultiParts > 5) {
cmdDone(true);
mState = States::RESET;
q->iv->radioStatistics.rxSuccess++;
mHeu.setGotAll(q->iv);
q->iv->miMultiParts = 0;
} else {
mHeu.setGotFragment(q->iv);
mState = States::WAIT;
}
//if(q->iv->miMultiParts > 5)
//closeRequest(q->iv, true);
//else
//if(q->iv->miMultiParts < 6)
// mState = States::WAIT;
/*if (mPayload[iv->id].multi_parts > 5) {
iv->setQueuedCmdFinished();
@ -571,8 +642,9 @@ class Communication : public CommQueue<> {
inline void miDataDecode(packet_t *p, const queue_s *q) {
record_t<> *rec = q->iv->getRecordStruct(RealTimeRunData_Debug); // choose the parser
rec->ts = q->ts;
q->iv->radioStatistics.rxSuccess++;
mState = States::RESET;
//mState = States::RESET;
if(q->iv->miMultiParts < 6)
q->iv->miMultiParts += 6;
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 :
@ -608,47 +680,51 @@ class Communication : public CommQueue<> {
miStsConsolidate(q, datachan, rec, p->packet[23], p->packet[24]);
if (p->packet[0] < (0x39 + ALL_FRAMES) ) {
//addImportant(q->iv, (q->cmd + 1));
//mPayload[iv->id].txCmd++;
//mPayload[iv->id].retransmits = 0; // reserve retransmissions for each response
//mPayload[iv->id].complete = false;
miNextRequest((p->packet[0] - ALL_FRAMES + 1), q);
mHeu.setGotFragment(q->iv);
} else {
miComplete(q->iv);
q->iv->miMultiParts = 7; // indicate we are ready
//miComplete(q->iv);
}
} else if((p->packet[0] == (MI_REQ_CH1 + ALL_FRAMES)) && (q->iv->type == INV_TYPE_2CH)) {
//addImportant(q->iv, MI_REQ_CH2);
miNextRequest(MI_REQ_CH2, q);
//use also miMultiParts here for better statistics?
mHeu.setGotFragment(q->iv);
//mHeu.setGotFragment(q->iv);
} else { // first data msg for 1ch, 2nd for 2ch
miComplete(q->iv);
q->iv->miMultiParts += 6; // indicate we are ready
//miComplete(q->iv);
}
}
inline void miNextRequest(uint8_t cmd, const queue_s *q) {
void miNextRequest(uint8_t cmd, const queue_s *q) {
incrAttempt(); // if function is called, we got something, and we necessarily need more transmissions for MI types...
if(*mSerialDebug) {
DPRINT_IVID(DBG_WARN, q->iv->id);
DBGPRINT(F("next request ("));
DBGPRINT(String(q->attempts));
DBGPRINT(F(" attempts left): 0x"));
DBGHEXLN(cmd);
}
//if(q->attempts) {
if(q->iv->miMultiParts == 7) {
//mHeu.setGotAll(q->iv);
q->iv->radioStatistics.rxSuccess++;
} else
//mHeu.setGotFragment(q->iv);
/*iv->radioStatistics.rxFail++; // got no complete payload*/
//q->iv->radioStatistics.retransmits++;
q->iv->radio->sendCmdPacket(q->iv, cmd, 0x00, true);
q->iv->radioStatistics.retransmits++;
mWaitTimeout = millis() + MI_TIMEOUT;
mWaitTimeout_min = mWaitTimeout;
q->iv->miMultiParts = 0;
q->iv->mGotFragment = 0;
mIsRetransmit = true;
chgCmd(cmd);
mState = States::WAIT;
/*} else {
add(q, true);
cmdDone();
mState = States::RESET;
}*/
//mState = States::WAIT;
}
inline void miStsConsolidate(const queue_s *q, uint8_t stschan, record_t<> *rec, uint8_t uState, uint8_t uEnum, uint8_t lState = 0, uint8_t lEnum = 0) {
void miStsConsolidate(const queue_s *q, 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 ) {
@ -697,12 +773,14 @@ class Communication : public CommQueue<> {
}
}
}
//if (mSerialDebug) {
if(*mSerialDebug) {
DPRINT(DBG_WARN, F("New state on CH"));
DBGPRINT(String(stschan)); DBGPRINT(F(" ("));
DBGPRINT(String(prntsts)); DBGPRINT(F("): "));
DBGPRINTLN(q->iv->getAlarmStr(prntsts));
//}
}
if(!q->iv->miMultiParts)
q->iv->miMultiParts = 1; // indicate we got status info (1+2 ch types)
}
if (!stsok) {
@ -712,16 +790,16 @@ class Communication : public CommQueue<> {
if (q->iv->alarmMesIndex < rec->record[q->iv->getPosByChFld(0, FLD_EVT, rec)]) {
q->iv->alarmMesIndex = rec->record[q->iv->getPosByChFld(0, FLD_EVT, rec)]; // seems there's no status per channel in 3rd gen. models?!?
//if (mSerialDebug) {
if (*mSerialDebug) {
DPRINT_IVID(DBG_INFO, q->iv->id);
DBGPRINT(F("alarm ID incremented to "));
DBGPRINTLN(String(q->iv->alarmMesIndex));
//}
}
}
}
inline void miComplete(Inverter<> *iv) {
void miComplete(Inverter<> *iv) {
if (*mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINTLN(F("got all data msgs"));
@ -749,12 +827,14 @@ class Communication : public CommQueue<> {
// update status state-machine,
if (ac_pow)
iv->isProducing();
mHeu.setGotAll(iv);
cmdDone(true);
//closeRequest(iv, iv->miMultiParts > 5);
//mHeu.setGotAll(iv);
//cmdDone(true);
if(NULL != mCbPayload)
(mCbPayload)(RealTimeRunData_Debug, iv);
mState = States::RESET; // everything ok, next request
//mState = States::RESET; // everything ok, next request
}
private:
@ -771,17 +851,23 @@ class Communication : public CommQueue<> {
private:
States mState = States::RESET;
uint32_t *mTimestamp;
bool *mPrivacyMode, *mSerialDebug;
bool *mPrivacyMode, *mSerialDebug, *mPrintWholeTrace;
uint16_t *mInverterGap;
uint32_t mWaitTimeout = 0;
uint32_t mWaitTimeout_min = 0;
std::array<frame_t, MAX_PAYLOAD_ENTRIES> mLocalBuf;
//bool mGotFragment = false;
bool mFirstTry = false;
bool mFirstTry = false; // see, if we should do a second try
bool mIsRetransmit = false; // we alrady had waited one complete cycle
uint16_t mlastTO_min = DEFAULT_TIMEOUT; // remember timeout_min for correct calculation
uint8_t mMaxFrameId;
uint8_t mPayload[MAX_BUFFER];
payloadListenerType mCbPayload = NULL;
alarmListenerType mCbAlarm = NULL;
Heuristic mHeu;
uint32_t mLastEmptyQueueMillis = 0;
bool mPrintSequenceDuration = false;
//States mDebugState = States::START;
};
#endif /*__COMMUNICATION_H__*/

166
src/hm/Heuristic.h

@ -8,10 +8,17 @@
#include "../utils/dbg.h"
#include "hmInverter.h"
#include "HeuristicInv.h"
#define RF_MAX_CHANNEL_ID 5
#define RF_MAX_QUALITY 4
#define RF_MIN_QUALTIY -6
#define RF_TEST_PERIOD_MAX_SEND_CNT 50
#define RF_TEST_PERIOD_MAX_FAIL_CNT 5
#define RF_TX_TEST_CHAN_1ST_USE 0xff
#define RF_TX_CHAN_QUALITY_GOOD 2
#define RF_TX_CHAN_QUALITY_OK 1
#define RF_TX_CHAN_QUALITY_LOW -1
#define RF_TX_CHAN_QUALITY_BAD -2
class Heuristic {
public:
@ -19,55 +26,121 @@ class Heuristic {
if((IV_HMS == iv->ivGen) || (IV_HMT == iv->ivGen))
return 0; // not used for these inverter types
mCycle++; // intended to overflow from time to time
if(mTestEn) {
iv->txRfChId = mCycle % RF_MAX_CHANNEL_ID;
DPRINTLN(DBG_INFO, F("heuristic test mode"));
return id2Ch(iv->txRfChId);
HeuristicInv *ih = &iv->heuristics;
// start with the next index: round robbin in case of same 'best' quality
uint8_t curId = (ih->txRfChId + 1) % RF_MAX_CHANNEL_ID;
ih->lastBestTxChId = ih->txRfChId;
ih->txRfChId = curId;
curId = (curId + 1) % RF_MAX_CHANNEL_ID;
for(uint8_t i = 1; i < RF_MAX_CHANNEL_ID; i++) {
if(ih->txRfQuality[curId] > ih->txRfQuality[ih->txRfChId])
ih->txRfChId = curId;
curId = (curId + 1) % RF_MAX_CHANNEL_ID;
}
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(ih->testPeriodSendCnt < 0xff)
ih->testPeriodSendCnt++;
if((ih->txRfChId == ih->lastBestTxChId) && (ih->testPeriodSendCnt >= RF_TEST_PERIOD_MAX_SEND_CNT)) {
if(ih->testPeriodFailCnt > RF_TEST_PERIOD_MAX_FAIL_CNT) {
// try round robbin another chan and see if it works even better
ih->testChId = (ih->testChId + 1) % RF_MAX_CHANNEL_ID;
if(ih->testChId == ih->txRfChId)
ih->testChId = (ih->testChId + 1) % RF_MAX_CHANNEL_ID;
// give it a fair chance but remember old status in case of immediate fail
ih->saveOldTestQuality = ih->txRfQuality[ih->testChId];
ih->txRfQuality[ih->testChId] = ih->txRfQuality[ih->txRfChId];
ih->txRfChId = ih->testChId;
ih->testChId = RF_TX_TEST_CHAN_1ST_USE; // mark the chan as a test and as 1st use during new test period
DPRINTLN(DBG_INFO, F("Test CH ") + String(id2Ch(ih->txRfChId)));
}
if(bestQuality == -6)
iv->txRfChId = (iv->txRfChId + 1) % RF_MAX_CHANNEL_ID; // next channel
else
iv->txRfChId = id; // best quality channel
return id2Ch(iv->txRfChId);
// start new test period
ih->testPeriodSendCnt = 0;
ih->testPeriodFailCnt = 0;
} else if(ih->txRfChId != ih->lastBestTxChId) {
// start new test period
ih->testPeriodSendCnt = 0;
ih->testPeriodFailCnt = 0;
}
void setGotAll(Inverter<> *iv) {
updateQuality(iv, 2); // GOOD
mTestEn = false;
return id2Ch(ih->txRfChId);
}
void setGotFragment(Inverter<> *iv) {
updateQuality(iv, 1); // OK
mTestEn = false;
void evalTxChQuality(Inverter<> *iv, bool crcPass, uint8_t retransmits, uint8_t rxFragments) {
HeuristicInv *ih = &iv->heuristics;
#if (DBG_DEBUG == DEBUG_LEVEL)
DPRINT(DBG_DEBUG, "eval ");
DBGPRINT(String(crcPass));
DBGPRINT(", ");
DBGPRINT(String(retransmits));
DBGPRINT(", ");
DBGPRINT(String(rxFragments));
DBGPRINT(", ");
DBGPRINTLN(String(ih->lastRxFragments));
#endif
if(ih->lastRxFragments == rxFragments) {
if(crcPass)
updateQuality(ih, RF_TX_CHAN_QUALITY_GOOD);
else if(!retransmits || isNewTxCh(ih)) { // nothing received: send probably lost
if(RF_TX_TEST_CHAN_1ST_USE == ih->testChId) {
// switch back to original quality
DPRINTLN(DBG_INFO, F("Test failed (-2)"));
ih->txRfQuality[ih->txRfChId] = ih->saveOldTestQuality;
}
void setGotNothing(Inverter<> *iv) {
if(!mTestEn) {
updateQuality(iv, -2); // BAD
mTestEn = true;
iv->txRfChId = (iv->txRfChId + 1) % RF_MAX_CHANNEL_ID;
updateQuality(ih, RF_TX_CHAN_QUALITY_BAD);
if(ih->testPeriodFailCnt < 0xff)
ih->testPeriodFailCnt++;
}
} else if(!ih->lastRxFragments && crcPass) {
if(!retransmits || isNewTxCh(ih)) {
// every fragment received successfull immediately
updateQuality(ih, RF_TX_CHAN_QUALITY_GOOD);
} else {
// every fragment received successfully
updateQuality(ih, RF_TX_CHAN_QUALITY_OK);
}
} else if(crcPass) {
if(isNewTxCh(ih)) {
// last Fragment successfully received on new send channel
updateQuality(ih, RF_TX_CHAN_QUALITY_OK);
}
} else if(!retransmits || isNewTxCh(ih)) {
// no complete receive for this send channel
if((rxFragments - ih->lastRxFragments) > 2) {
// graceful evaluation for big inverters that have to send 4 answer packets
updateQuality(ih, RF_TX_CHAN_QUALITY_OK);
} else if((rxFragments - ih->lastRxFragments) < 2) {
if(RF_TX_TEST_CHAN_1ST_USE == ih->testChId) {
// switch back to original quality
DPRINTLN(DBG_INFO, F("Test failed (-1)"));
ih->txRfQuality[ih->txRfChId] = ih->saveOldTestQuality;
}
updateQuality(ih, RF_TX_CHAN_QUALITY_LOW);
if(ih->testPeriodFailCnt < 0xff)
ih->testPeriodFailCnt++;
} // else: _QUALITY_NEUTRAL, keep any test channel
} // else: dont overestimate burst distortion
ih->testChId = ih->txRfChId; // reset to best
ih->lastRxFragments = rxFragments;
}
void printStatus(Inverter<> *iv) {
DPRINT_IVID(DBG_INFO, iv->id);
DBGPRINT(F("Radio infos:"));
if((IV_HMS != iv->ivGen) && (IV_HMT != iv->ivGen)) {
for(uint8_t i = 0; i < RF_MAX_CHANNEL_ID; i++) {
DBGPRINT(F(" "));
DBGPRINT(String(iv->txRfQuality[i]));
DBGPRINT(String(iv->heuristics.txRfQuality[i]));
}
DBGPRINT(F(" | t: "));
DBGPRINT(F(" |"));
}
DBGPRINT(F(" t: "));
DBGPRINT(String(iv->radioStatistics.txCnt));
DBGPRINT(F(", s: "));
DBGPRINT(String(iv->radioStatistics.rxSuccess));
@ -76,20 +149,23 @@ class Heuristic {
DBGPRINT(F(", n: "));
DBGPRINT(String(iv->radioStatistics.rxFailNoAnser));
DBGPRINT(F(" | p: ")); // better debugging for helpers...
if((IV_HMS == iv->ivGen) || (IV_HMT == iv->ivGen))
DBGPRINTLN(String(iv->config->powerLevel-10));
else
DBGPRINTLN(String(iv->config->powerLevel));
}
bool getTestModeEnabled(void) {
return mTestEn;
private:
bool isNewTxCh(HeuristicInv *ih) {
return ih->txRfChId != ih->lastBestTxChId;
}
private:
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;
void updateQuality(HeuristicInv *ih, uint8_t quality) {
ih->txRfQuality[ih->txRfChId] += quality;
if(ih->txRfQuality[ih->txRfChId] > RF_MAX_QUALITY)
ih->txRfQuality[ih->txRfChId] = RF_MAX_QUALITY;
else if(ih->txRfQuality[ih->txRfChId] < RF_MIN_QUALTIY)
ih->txRfQuality[ih->txRfChId] = RF_MIN_QUALTIY;
}
inline uint8_t id2Ch(uint8_t id) {
@ -100,13 +176,11 @@ class Heuristic {
case 3: return 61;
case 4: return 75;
}
return 0; // standard
return 3; // standard
}
private:
uint8_t mChList[5] = {03, 23, 40, 61, 75};
bool mTestEn = false;
uint8_t mCycle = 0;
};

32
src/hm/HeuristicInv.h

@ -0,0 +1,32 @@
//-----------------------------------------------------------------------------
// 2023 Ahoy, https://github.com/lumpapu/ahoy
// Creative Commons - http://creativecommons.org/licenses/by-nc-sa/4.0/deed
//-----------------------------------------------------------------------------
#ifndef __HEURISTIC_INV_H__
#define __HEURISTIC_INV_H__
#define RF_MAX_CHANNEL_ID 5
#define RF_MAX_QUALITY 4
#define RF_MIN_QUALTIY -6
#define RF_NA -99
class HeuristicInv {
public:
HeuristicInv() {
memset(txRfQuality, -6, RF_MAX_CHANNEL_ID);
}
public:
int8_t txRfQuality[RF_MAX_CHANNEL_ID]; // heuristics tx quality (check 'Heuristics.h')
uint8_t txRfChId = 0; // RF TX channel id
uint8_t lastBestTxChId = 0;
uint8_t testPeriodSendCnt = 0;
uint8_t testPeriodFailCnt = 0;
uint8_t testChId = 0;
int8_t saveOldTestQuality = -6;
uint8_t lastRxFragments = 0;
};
#endif /*__HEURISTIC_INV_H__*/

11
src/hm/hmInverter.h

@ -12,6 +12,7 @@
#endif
#include "hmDefines.h"
#include "HeuristicInv.h"
#include "../hms/hmsDefines.h"
#include <memory>
#include <queue>
@ -128,11 +129,11 @@ class Inverter {
uint8_t miMultiParts; // helper info for MI multiframe msgs
uint8_t outstandingFrames; // helper info to count difference between expected and received frames
bool mGotFragment; // shows if inverter has sent at least one fragment
uint8_t curFrmCnt; // count received frames in current loop
bool mGotLastMsg; // shows if inverter has already finished transmission cycle
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
HeuristicInv heuristics;
uint8_t curCmtFreq; // current used CMT frequency, used to check if freq. was changed during runtime
bool commEnabled; // 'pause night communication' sets this field to false
@ -160,7 +161,7 @@ class Inverter {
commEnabled = true;
memset(&radioStatistics, 0, sizeof(statistics_t));
memset(txRfQuality, -6, 5);
memset(heuristics.txRfQuality, -6, 5);
memset(mOffYD, 0, sizeof(float) * 6);
memset(mLastYD, 0, sizeof(float) * 6);
@ -391,6 +392,10 @@ class Inverter {
bool isAvailable() {
bool avail = false;
if((recordMeas.ts == 0) && (recordInfo.ts == 0) && (recordConfig.ts == 0) && (recordAlarm.ts == 0))
return false;
if((*timestamp - recordMeas.ts) < INVERTER_INACT_THRES_SEC)
avail = true;
if((*timestamp - recordInfo.ts) < INVERTER_INACT_THRES_SEC)

134
src/hm/hmRadio.h

@ -9,6 +9,10 @@
#include <RF24.h>
#include "SPI.h"
#include "radio.h"
#include "../config/config.h"
#if defined(CONFIG_IDF_TARGET_ESP32S3) && defined(ETHERNET)
#include "nrfHal.h"
#endif
#define SPI_SPEED 1000000
@ -28,66 +32,72 @@ const char* const rf24AmpPowerNames[] = {"MIN", "LOW", "HIGH", "MAX"};
template <uint8_t IRQ_PIN = DEF_NRF_IRQ_PIN, uint8_t CE_PIN = DEF_NRF_CE_PIN, uint8_t CS_PIN = DEF_NRF_CS_PIN, uint8_t AMP_PWR = RF24_PA_LOW, uint8_t SCLK_PIN = DEF_NRF_SCLK_PIN, uint8_t MOSI_PIN = DEF_NRF_MOSI_PIN, uint8_t MISO_PIN = DEF_NRF_MISO_PIN, uint32_t DTU_SN = 0x81001765>
class HmRadio : public Radio {
public:
HmRadio() : mNrf24(CE_PIN, CS_PIN, SPI_SPEED) {
HmRadio() {
mDtuSn = DTU_SN;
mIrqRcvd = false;
#if defined(CONFIG_IDF_TARGET_ESP32S3) && defined(ETHERNET)
mNrf24.reset(new RF24());
#else
mNrf24.reset(new RF24(CE_PIN, CS_PIN, SPI_SPEED));
#endif
}
~HmRadio() {}
void setup(bool *serialDebug, bool *privacyMode, uint8_t irq = IRQ_PIN, uint8_t ce = CE_PIN, uint8_t cs = CS_PIN, uint8_t sclk = SCLK_PIN, uint8_t mosi = MOSI_PIN, uint8_t miso = MISO_PIN) {
void setup(bool *serialDebug, bool *privacyMode, bool *printWholeTrace, uint8_t irq = IRQ_PIN, uint8_t ce = CE_PIN, uint8_t cs = CS_PIN, uint8_t sclk = SCLK_PIN, uint8_t mosi = MOSI_PIN, uint8_t miso = MISO_PIN) {
DPRINTLN(DBG_VERBOSE, F("hmRadio.h:setup"));
pinMode(irq, INPUT_PULLUP);
mSerialDebug = serialDebug;
mPrivacyMode = privacyMode;
if(*mSerialDebug) {
DPRINT(DBG_VERBOSE, F("hmRadio.h : HmRadio():mNrf24(CE_PIN: "));
DBGPRINT(String(CE_PIN));
DBGPRINT(F(", CS_PIN: "));
DBGPRINT(String(CS_PIN));
DBGPRINT(F(", SPI_SPEED: "));
DBGPRINT(String(SPI_SPEED));
DBGPRINTLN(F(")"));
}
mPrintWholeTrace = printWholeTrace;
generateDtuSn();
DTU_RADIO_ID = ((uint64_t)(((mDtuSn >> 24) & 0xFF) | ((mDtuSn >> 8) & 0xFF00) | ((mDtuSn << 8) & 0xFF0000) | ((mDtuSn << 24) & 0xFF000000)) << 8) | 0x01;
#ifdef ESP32
#if defined(CONFIG_IDF_TARGET_ESP32S3) && defined(ETHERNET)
mNrfHal.init(mosi, miso, sclk, cs, ce);
mNrf24.reset(new RF24(&mNrfHal));
#else
#if CONFIG_IDF_TARGET_ESP32C3 || CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3
mSpi = new SPIClass(HSPI);
mSpi.reset(new SPIClass(HSPI));
#else
mSpi = new SPIClass(VSPI);
mSpi.reset(new SPIClass(VSPI));
#endif
mSpi->begin(sclk, miso, mosi, cs);
#endif
#else
//the old ESP82xx cannot freely place their SPI pins
mSpi = new SPIClass();
mSpi.reset(new SPIClass());
mSpi->begin();
#endif
mNrf24.begin(mSpi, ce, cs);
mNrf24.setRetries(3, 15); // 3*250us + 250us and 15 loops -> 15ms
mNrf24.setChannel(mRfChLst[mRxChIdx]);
mNrf24.startListening();
mNrf24.setDataRate(RF24_250KBPS);
mNrf24.setAutoAck(true);
mNrf24.enableDynamicAck();
mNrf24.enableDynamicPayloads();
mNrf24.setCRCLength(RF24_CRC_16);
mNrf24.setAddressWidth(5);
mNrf24.openReadingPipe(1, reinterpret_cast<uint8_t*>(&DTU_RADIO_ID));
#if defined(CONFIG_IDF_TARGET_ESP32S3) && defined(ETHERNET)
mNrf24->begin();
#else
mNrf24->begin(mSpi.get(), ce, cs);
#endif
mNrf24->setRetries(3, 15); // 3*250us + 250us and 15 loops -> 15ms
mNrf24->setChannel(mRfChLst[mRxChIdx]);
mNrf24->startListening();
mNrf24->setDataRate(RF24_250KBPS);
mNrf24->setAutoAck(true);
mNrf24->enableDynamicAck();
mNrf24->enableDynamicPayloads();
mNrf24->setCRCLength(RF24_CRC_16);
mNrf24->setAddressWidth(5);
mNrf24->openReadingPipe(1, reinterpret_cast<uint8_t*>(&DTU_RADIO_ID));
// enable all receiving interrupts
mNrf24.maskIRQ(false, false, false);
mNrf24->maskIRQ(false, false, false);
mNrf24.setPALevel(1); // low is default
mNrf24->setPALevel(1); // low is default
if(mNrf24.isChipConnected()) {
if(mNrf24->isChipConnected()) {
DPRINTLN(DBG_INFO, F("Radio Config:"));
mNrf24.printPrettyDetails();
mNrf24->printPrettyDetails();
DPRINT(DBG_INFO, F("DTU_SN: 0x"));
DBGPRINTLN(String(mDtuSn, HEX));
} else
@ -99,22 +109,20 @@ class HmRadio : public Radio {
return; // nothing to do
mIrqRcvd = false;
bool tx_ok, tx_fail, rx_ready;
mNrf24.whatHappened(tx_ok, tx_fail, rx_ready); // resets the IRQ pin to HIGH
mNrf24.flush_tx(); // empty TX FIFO
mNrf24->whatHappened(tx_ok, tx_fail, rx_ready); // resets the IRQ pin to HIGH
mNrf24->flush_tx(); // empty TX FIFO
// start listening
//mNrf24.setChannel(23);
//mRxChIdx = 0;
mNrf24.setChannel(mRfChLst[mRxChIdx]);
mNrf24.startListening();
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) {
while (micros() < startMicros) { // listen (4088us or?) 5110us to each channel
uint32_t startMicros = micros();
uint32_t loopMillis = millis();
while ((millis() - loopMillis) < 400) {
while ((micros() - startMicros) < 5110) { // listen (4088us or?) 5110us to each channel
if (mIrqRcvd) {
mIrqRcvd = false;
@ -127,8 +135,8 @@ class HmRadio : public Radio {
// switch to next RX channel
if(++mRxChIdx >= RF_CHANNELS)
mRxChIdx = 0;
mNrf24.setChannel(mRfChLst[mRxChIdx]);
startMicros = micros() + 5110;
mNrf24->setChannel(mRfChLst[mRxChIdx]);
startMicros = micros();
}
// not finished but time is over
if(++mRxChIdx >= RF_CHANNELS)
@ -139,7 +147,7 @@ class HmRadio : public Radio {
bool isChipConnected(void) {
//DPRINTLN(DBG_VERBOSE, F("hmRadio.h:isChipConnected"));
return mNrf24.isChipConnected();
return mNrf24->isChipConnected();
}
void sendControlPacket(Inverter<> *iv, uint8_t cmd, uint16_t *data, bool isRetransmit) {
@ -228,31 +236,31 @@ class HmRadio : public Radio {
}
uint8_t getDataRate(void) {
if(!mNrf24.isChipConnected())
if(!mNrf24->isChipConnected())
return 3; // unknown
return mNrf24.getDataRate();
return mNrf24->getDataRate();
}
bool isPVariant(void) {
return mNrf24.isPVariant();
return mNrf24->isPVariant();
}
private:
inline bool getReceived(void) {
bool tx_ok, tx_fail, rx_ready;
mNrf24.whatHappened(tx_ok, tx_fail, rx_ready); // resets the IRQ pin to HIGH
mNrf24->whatHappened(tx_ok, tx_fail, rx_ready); // resets the IRQ pin to HIGH
bool isLastPackage = false;
while(mNrf24.available()) {
while(mNrf24->available()) {
uint8_t len;
len = mNrf24.getDynamicPayloadSize(); // if payload size > 32, corrupt payload has been flushed
len = mNrf24->getDynamicPayloadSize(); // if payload size > 32, corrupt payload has been flushed
if (len > 0) {
packet_t p;
p.ch = mRfChLst[mRxChIdx];
p.len = (len > MAX_RF_PAYLOAD_SIZE) ? MAX_RF_PAYLOAD_SIZE : len;
p.rssi = mNrf24.testRPD() ? -64 : -75;
p.rssi = mNrf24->testRPD() ? -64 : -75;
p.millis = millis() - mMillis;
mNrf24.read(p.packet, p.len);
mNrf24->read(p.packet, p.len);
if (p.packet[0] != 0x00) {
if(!checkIvSerial(p.packet, mLastIv)) {
DPRINT(DBG_WARN, "RX other inverter ");
@ -280,11 +288,11 @@ class HmRadio : public Radio {
}
void sendPacket(Inverter<> *iv, uint8_t len, bool isRetransmit, bool appendCrc16=true) {
mNrf24.setPALevel(iv->config->powerLevel & 0x03);
mNrf24->setPALevel(iv->config->powerLevel & 0x03);
updateCrcs(&len, appendCrc16);
// set TX and RX channels
mTxChIdx = mRfChLst[iv->txRfChId];
mTxChIdx = mRfChLst[iv->heuristics.txRfChId];
if(*mSerialDebug) {
DPRINT_IVID(DBG_INFO, iv->id);
@ -293,16 +301,19 @@ class HmRadio : public Radio {
DBGPRINT(" CH");
DBGPRINT(String(mTxChIdx));
DBGPRINT(F(" | "));
if(*mPrintWholeTrace) {
if(*mPrivacyMode)
ah::dumpBuf(mTxBuf, len, 1, 4);
else
ah::dumpBuf(mTxBuf, len);
} else
DBGHEXLN(mTxBuf[9]);
}
mNrf24.stopListening();
mNrf24.setChannel(mTxChIdx);
mNrf24.openWritingPipe(reinterpret_cast<uint8_t*>(&iv->radioId.u64));
mNrf24.startWrite(mTxBuf, len, false); // false = request ACK response
mNrf24->stopListening();
mNrf24->setChannel(mTxChIdx);
mNrf24->openWritingPipe(reinterpret_cast<uint8_t*>(&iv->radioId.u64));
mNrf24->startWrite(mTxBuf, len, false); // false = request ACK response
mMillis = millis();
mLastIv = iv;
@ -331,8 +342,11 @@ class HmRadio : public Radio {
bool mGotLastMsg = false;
uint32_t mMillis;
SPIClass* mSpi;
RF24 mNrf24;
std::unique_ptr<SPIClass> mSpi;
std::unique_ptr<RF24> mNrf24;
#if defined(CONFIG_IDF_TARGET_ESP32S3) && defined(ETHERNET)
nrfHal mNrfHal;
#endif
Inverter<> *mLastIv = NULL;
};

218
src/hm/nrfHal.h

@ -0,0 +1,218 @@
//-----------------------------------------------------------------------------
// 2023 Ahoy, https://www.mikrocontroller.net/topic/525778
// Creative Commons - http://creativecommons.org/licenses/by-nc-sa/3.0/de/
//-----------------------------------------------------------------------------
#ifndef __NRF_HAL_H__
#define __NRF_HAL_H__
#pragma once
#include "../utils/spiPatcher.h"
#include <esp_rom_gpio.h>
#include <RF24_hal.h>
#define NRF_MAX_TRANSFER_SZ 64
#define NRF_DEFAULT_SPI_SPEED 10000000 // 10 MHz
class nrfHal: public RF24_hal, public SpiPatcherHandle {
public:
nrfHal() {
mSpiPatcher = SpiPatcher::getInstance(SPI2_HOST);
}
void patch() override {
esp_rom_gpio_connect_out_signal(mPinMosi, spi_periph_signal[mHostDevice].spid_out, false, false);
esp_rom_gpio_connect_in_signal(mPinMiso, spi_periph_signal[mHostDevice].spiq_in, false);
esp_rom_gpio_connect_out_signal(mPinClk, spi_periph_signal[mHostDevice].spiclk_out, false, false);
}
void unpatch() override {
esp_rom_gpio_connect_out_signal(mPinMosi, SIG_GPIO_OUT_IDX, false, false);
esp_rom_gpio_connect_in_signal(mPinMiso, GPIO_MATRIX_CONST_ZERO_INPUT, false);
esp_rom_gpio_connect_out_signal(mPinClk, SIG_GPIO_OUT_IDX, false, false);
}
void init(int8_t mosi, int8_t miso, int8_t sclk, int8_t cs, int8_t en, int32_t speed = NRF_DEFAULT_SPI_SPEED) {
mPinMosi = static_cast<gpio_num_t>(mosi);
mPinMiso = static_cast<gpio_num_t>(miso);
mPinClk = static_cast<gpio_num_t>(sclk);
mPinCs = static_cast<gpio_num_t>(cs);
mPinEn = static_cast<gpio_num_t>(en);
mSpiSpeed = speed;
mHostDevice = mSpiPatcher->getDevice();
gpio_reset_pin(mPinMosi);
gpio_set_direction(mPinMosi, GPIO_MODE_OUTPUT);
gpio_set_level(mPinMosi, 1);
gpio_reset_pin(mPinMiso);
gpio_set_direction(mPinMiso, GPIO_MODE_INPUT);
gpio_reset_pin(mPinClk);
gpio_set_direction(mPinClk, GPIO_MODE_OUTPUT);
gpio_set_level(mPinClk, 0);
gpio_reset_pin(mPinCs);
spi_device_interface_config_t devcfg = {
.command_bits = 0,
.address_bits = 0,
.dummy_bits = 0,
.mode = 0,
.duty_cycle_pos = 0,
.cs_ena_pretrans = 0,
.cs_ena_posttrans = 0,
.clock_speed_hz = mSpiSpeed,
.input_delay_ns = 0,
.spics_io_num = mPinCs,
.flags = 0,
.queue_size = 1,
.pre_cb = nullptr,
.post_cb = nullptr
};
ESP_ERROR_CHECK(spi_bus_add_device(mHostDevice, &devcfg, &spi));
gpio_reset_pin(mPinEn);
gpio_set_direction(mPinEn, GPIO_MODE_OUTPUT);
gpio_set_level(mPinEn, 0);
}
bool begin() override {
return true;
}
void end() override {}
void ce(bool level) override {
gpio_set_level(mPinEn, level);
}
uint8_t write(uint8_t cmd, const uint8_t* buf, uint8_t len) override {
uint8_t data[NRF_MAX_TRANSFER_SZ];
data[0] = cmd;
std::copy(&buf[0], &buf[len], &data[1]);
request_spi();
size_t spiLen = (static_cast<size_t>(len) + 1u) << 3;
spi_transaction_t t = {
.flags = 0,
.cmd = 0,
.addr = 0,
.length = spiLen,
.rxlength = spiLen,
.user = NULL,
.tx_buffer = data,
.rx_buffer = data
};
ESP_ERROR_CHECK(spi_device_polling_transmit(spi, &t));
release_spi();
return data[0]; // status
}
uint8_t write(uint8_t cmd, const uint8_t* buf, uint8_t data_len, uint8_t blank_len) override {
uint8_t data[NRF_MAX_TRANSFER_SZ];
data[0] = cmd;
memset(data, 0, NRF_MAX_TRANSFER_SZ);
std::copy(&buf[0], &buf[data_len], &data[1]);
request_spi();
size_t spiLen = (static_cast<size_t>(data_len) + static_cast<size_t>(blank_len) + 1u) << 3;
spi_transaction_t t = {
.flags = 0,
.cmd = 0,
.addr = 0,
.length = spiLen,
.rxlength = spiLen,
.user = NULL,
.tx_buffer = data,
.rx_buffer = data
};
ESP_ERROR_CHECK(spi_device_polling_transmit(spi, &t));
release_spi();
return data[0]; // status
}
uint8_t read(uint8_t cmd, uint8_t* buf, uint8_t len) override {
uint8_t data[NRF_MAX_TRANSFER_SZ];
data[0] = cmd;
memset(&data[1], 0xff, len);
request_spi();
size_t spiLen = (static_cast<size_t>(len) + 1u) << 3;
spi_transaction_t t = {
.flags = 0,
.cmd = 0,
.addr = 0,
.length = spiLen,
.rxlength = spiLen,
.user = NULL,
.tx_buffer = data,
.rx_buffer = data
};
ESP_ERROR_CHECK(spi_device_polling_transmit(spi, &t));
release_spi();
std::copy(&data[1], &data[len+1], buf);
return data[0]; // status
}
uint8_t read(uint8_t cmd, uint8_t* buf, uint8_t data_len, uint8_t blank_len) override {
uint8_t data[NRF_MAX_TRANSFER_SZ];
data[0] = cmd;
memset(&data[1], 0xff, (data_len + blank_len));
request_spi();
size_t spiLen = (static_cast<size_t>(data_len) + static_cast<size_t>(blank_len) + 1u) << 3;
spi_transaction_t t = {
.flags = 0,
.cmd = 0,
.addr = 0,
.length = spiLen,
.rxlength = spiLen,
.user = NULL,
.tx_buffer = data,
.rx_buffer = data
};
ESP_ERROR_CHECK(spi_device_polling_transmit(spi, &t));
release_spi();
std::copy(&data[1], &data[data_len+1], buf);
return data[0]; // status
}
private:
inline void request_spi() {
mSpiPatcher->request(this);
}
inline void release_spi() {
mSpiPatcher->release();
}
private:
gpio_num_t mPinMosi = GPIO_NUM_NC;
gpio_num_t mPinMiso = GPIO_NUM_NC;
gpio_num_t mPinClk = GPIO_NUM_NC;
gpio_num_t mPinCs = GPIO_NUM_NC;
gpio_num_t mPinEn = GPIO_NUM_NC;
int32_t mSpiSpeed = NRF_DEFAULT_SPI_SPEED;
spi_host_device_t mHostDevice;
spi_device_handle_t spi;
SpiPatcher *mSpiPatcher;
};
#endif /*__NRF_HAL_H__*/

13
src/hm/radio.h

@ -24,11 +24,9 @@ class Radio {
virtual void sendControlPacket(Inverter<> *iv, uint8_t cmd, uint16_t *data, bool isRetransmit) = 0;
virtual bool switchFrequency(Inverter<> *iv, uint32_t fromkHz, uint32_t tokHz) { return true; }
virtual bool switchFrequencyCh(Inverter<> *iv, uint8_t fromCh, uint8_t toCh) { return true; }
virtual void loop(void) {};
virtual bool isChipConnected(void) { return false; }
bool get() {
return !mBufCtrl.empty();
}
virtual void loop(void) {};
void handleIntr(void) {
mIrqRcvd = true;
@ -61,6 +59,10 @@ class Radio {
sendPacket(iv, 24, isRetransmit);
}
uint32_t getDTUSn(void) {
return mDtuSn;
}
public:
std::queue<packet_t> mBufCtrl;
@ -107,8 +109,7 @@ class Radio {
uint32_t mDtuSn;
volatile bool mIrqRcvd;
bool *mSerialDebug;
bool *mPrivacyMode;
bool *mSerialDebug, *mPrivacyMode, *mPrintWholeTrace;
uint8_t mTxBuf[MAX_RF_PAYLOAD_SIZE];
};

19
src/hms/cmt2300a.h

@ -6,7 +6,11 @@
#ifndef __CMT2300A_H__
#define __CMT2300A_H__
#if defined(CONFIG_IDF_TARGET_ESP32S3) && defined(ETHERNET)
#include "cmtHal.h"
#else
#include "esp32_3wSpi.h"
#endif
// detailed register infos from AN142_CMT2300AW_Quick_Start_Guide-Rev0.8.pdf
@ -209,19 +213,12 @@ static uint8_t cmtConfig[0x60] PROGMEM {
enum {CMT_SUCCESS = 0, CMT_ERR_SWITCH_STATE, CMT_ERR_TX_PENDING, CMT_FIFO_EMPTY, CMT_ERR_RX_IN_FIFO};
template<class SPI>
class Cmt2300a {
typedef SPI SpiType;
public:
Cmt2300a() {}
void setup(uint8_t pinSclk, uint8_t pinSdio, uint8_t pinCsb, uint8_t pinFcsb) {
mSpi.setup(pinSclk, pinSdio, pinCsb, pinFcsb);
init();
}
void setup() {
mSpi.setup();
mSpi.init(pinSdio, pinSclk, pinCsb, pinFcsb);
init();
}
@ -483,7 +480,11 @@ class Cmt2300a {
return mSpi.readReg(CMT2300A_CUS_MODE_STA) & CMT2300A_MASK_CHIP_MODE_STA;
}
SpiType mSpi;
#if defined(CONFIG_IDF_TARGET_ESP32S3) && defined(ETHERNET)
cmtHal mSpi;
#else
esp32_3wSpi mSpi;
#endif
uint8_t mCnt;
bool mTxPending;
bool mInRxMode;

196
src/hms/cmtHal.h

@ -0,0 +1,196 @@
//-----------------------------------------------------------------------------
// 2023 Ahoy, https://www.mikrocontroller.net/topic/525778
// Creative Commons - http://creativecommons.org/licenses/by-nc-sa/3.0/de/
//-----------------------------------------------------------------------------
#ifndef __CMT_HAL_H__
#define __CMT_HAL_H__
#pragma once
#include "../utils/spiPatcher.h"
#include <driver/gpio.h>
#define CMT_DEFAULT_SPI_SPEED 4000000 // 4 MHz
class cmtHal : public SpiPatcherHandle {
public:
cmtHal() {
mSpiPatcher = SpiPatcher::getInstance(SPI2_HOST);
}
void patch() override {
esp_rom_gpio_connect_out_signal(mPinSdio, spi_periph_signal[mHostDevice].spid_out, false, false);
esp_rom_gpio_connect_in_signal(mPinSdio, spi_periph_signal[mHostDevice].spid_in, false);
esp_rom_gpio_connect_out_signal(mPinClk, spi_periph_signal[mHostDevice].spiclk_out, false, false);
}
void unpatch() override {
esp_rom_gpio_connect_out_signal(mPinSdio, SIG_GPIO_OUT_IDX, false, false);
esp_rom_gpio_connect_in_signal(mPinSdio, GPIO_MATRIX_CONST_ZERO_INPUT, false);
esp_rom_gpio_connect_out_signal(mPinClk, SIG_GPIO_OUT_IDX, false, false);
}
void init(int8_t sdio, int8_t clk, int8_t cs, int8_t fcs, int32_t speed = CMT_DEFAULT_SPI_SPEED) {
mPinSdio = static_cast<gpio_num_t>(sdio);
mPinClk = static_cast<gpio_num_t>(clk);
mPinCs = static_cast<gpio_num_t>(cs);
mPinFcs = static_cast<gpio_num_t>(fcs);
mSpiSpeed = speed;
mHostDevice = mSpiPatcher->getDevice();
gpio_reset_pin(mPinSdio);
gpio_set_direction(mPinSdio, GPIO_MODE_INPUT_OUTPUT);
gpio_set_level(mPinSdio, 1);
gpio_reset_pin(mPinClk);
gpio_set_direction(mPinClk, GPIO_MODE_OUTPUT);
gpio_set_level(mPinClk, 0);
gpio_reset_pin(mPinCs);
spi_device_interface_config_t devcfg_reg = {
.command_bits = 1,
.address_bits = 7,
.dummy_bits = 0,
.mode = 0,
.duty_cycle_pos = 0,
.cs_ena_pretrans = 1,
.cs_ena_posttrans = 1,
.clock_speed_hz = mSpiSpeed,
.input_delay_ns = 0,
.spics_io_num = mPinCs,
.flags = SPI_DEVICE_HALFDUPLEX | SPI_DEVICE_3WIRE,
.queue_size = 1,
.pre_cb = nullptr,
.post_cb = nullptr
};
ESP_ERROR_CHECK(spi_bus_add_device(mHostDevice, &devcfg_reg, &spi_reg));
gpio_reset_pin(mPinFcs);
spi_device_interface_config_t devcfg_fifo = {
.command_bits = 0,
.address_bits = 0,
.dummy_bits = 0,
.mode = 0,
.duty_cycle_pos = 0,
.cs_ena_pretrans = 2,
.cs_ena_posttrans = static_cast<uint8_t>(2 * mSpiSpeed / 1000000), // >2 us
.clock_speed_hz = mSpiSpeed,
.input_delay_ns = 0,
.spics_io_num = mPinFcs,
.flags = SPI_DEVICE_HALFDUPLEX | SPI_DEVICE_3WIRE,
.queue_size = 1,
.pre_cb = nullptr,
.post_cb = nullptr
};
ESP_ERROR_CHECK(spi_bus_add_device(mHostDevice, &devcfg_fifo, &spi_fifo));
}
uint8_t readReg(uint8_t addr) {
uint8_t data;
request_spi();
spi_transaction_t t = {
.flags = 0,
.cmd = 1,
.addr = addr,
.length = 0,
.rxlength = 8,
.user = NULL,
.tx_buffer = NULL,
.rx_buffer = &data
};
ESP_ERROR_CHECK(spi_device_polling_transmit(spi_reg, &t));
release_spi();
return data;
}
void writeReg(uint8_t addr, uint8_t data) {
request_spi();
spi_transaction_t t = {
.flags = 0,
.cmd = 0,
.addr = addr,
.length = 8,
.rxlength = 0,
.user = NULL,
.tx_buffer = &data,
.rx_buffer = NULL
};
ESP_ERROR_CHECK(spi_device_polling_transmit(spi_reg, &t));
release_spi();
}
void readFifo(uint8_t buf[], uint8_t *len, uint8_t maxlen) {
request_spi();
spi_transaction_t t = {
.flags = 0,
.cmd = 0,
.addr = 0,
.length = 0,
.rxlength = 8,
.user = NULL,
.tx_buffer = NULL,
.rx_buffer = NULL
};
for (uint8_t i = 0; i < maxlen; i++) {
if(0 == i)
t.rx_buffer = len;
else
t.rx_buffer = buf + i - 1;
ESP_ERROR_CHECK(spi_device_polling_transmit(spi_fifo, &t));
}
release_spi();
}
void writeFifo(const uint8_t buf[], uint16_t len) {
request_spi();
spi_transaction_t t = {
.flags = 0,
.cmd = 0,
.addr = 0,
.length = 8,
.rxlength = 0,
.user = NULL,
.tx_buffer = NULL,
.rx_buffer = NULL
};
for (uint16_t i = 0; i < len; i++) {
t.tx_buffer = buf + i;
ESP_ERROR_CHECK(spi_device_polling_transmit(spi_fifo, &t));
}
release_spi();
}
private:
inline void request_spi() {
mSpiPatcher->request(this);
}
inline void release_spi() {
mSpiPatcher->release();
}
private:
gpio_num_t mPinSdio = GPIO_NUM_NC;
gpio_num_t mPinClk = GPIO_NUM_NC;
gpio_num_t mPinCs = GPIO_NUM_NC;
gpio_num_t mPinFcs = GPIO_NUM_NC;
int32_t mSpiSpeed = CMT_DEFAULT_SPI_SPEED;
spi_host_device_t mHostDevice;
spi_device_handle_t spi_reg, spi_fifo;
SpiPatcher *mSpiPatcher;
};
#endif /*__CMT_HAL_H__*/

2
src/hms/esp32_3wSpi.h

@ -29,7 +29,7 @@ class esp32_3wSpi {
mInitialized = false;
}
void setup(uint8_t pinSclk = DEF_CMT_SCLK, uint8_t pinSdio = DEF_CMT_SDIO, uint8_t pinCsb = DEF_CMT_CSB, uint8_t pinFcsb = DEF_CMT_FCSB) {
void init(uint8_t pinSdio = DEF_CMT_SDIO, uint8_t pinSclk = DEF_CMT_SCLK, uint8_t pinCsb = DEF_CMT_CSB, uint8_t pinFcsb = DEF_CMT_FCSB) {
paramLock = xSemaphoreCreateMutex();
spi_bus_config_t buscfg = {
.mosi_io_num = pinSdio,

20
src/hms/hmsRadio.h

@ -9,28 +9,21 @@
#include "cmt2300a.h"
#include "../hm/radio.h"
template<class SPI, uint32_t DTU_SN = 0x81001765>
template<uint32_t DTU_SN = 0x81001765>
class CmtRadio : public Radio {
typedef SPI SpiType;
typedef Cmt2300a<SpiType> CmtType;
typedef Cmt2300a CmtType;
public:
CmtRadio() {
mDtuSn = DTU_SN;
mCmtAvail = false;
}
void setup(bool *serialDebug, bool *privacyMode, uint8_t pinSclk, uint8_t pinSdio, uint8_t pinCsb, uint8_t pinFcsb, bool genDtuSn = true) {
void setup(bool *serialDebug, bool *privacyMode, bool *printWholeTrace, uint8_t pinSclk, uint8_t pinSdio, uint8_t pinCsb, uint8_t pinFcsb, bool genDtuSn = true) {
mCmt.setup(pinSclk, pinSdio, pinCsb, pinFcsb);
reset(genDtuSn);
mPrivacyMode = privacyMode;
mSerialDebug = serialDebug;
}
void setup(bool *serialDebug, bool *privacyMode, bool genDtuSn = true) {
mCmt.setup();
reset(genDtuSn);
mPrivacyMode = privacyMode;
mSerialDebug = serialDebug;
mPrintWholeTrace = printWholeTrace;
}
void loop() {
@ -44,7 +37,7 @@ class CmtRadio : public Radio {
}
}
bool isConnected() {
bool isChipConnected(void) {
return mCmtAvail;
}
@ -97,10 +90,13 @@ class CmtRadio : public Radio {
DBGPRINT(F("TX "));
DBGPRINT(String(mCmt.getFreqKhz()/1000.0f));
DBGPRINT(F("Mhz | "));
if(*mPrintWholeTrace) {
if(*mPrivacyMode)
ah::dumpBuf(mTxBuf, len, 1, 4);
else
ah::dumpBuf(mTxBuf, len);
} else
DBGHEXLN(mTxBuf[9]);
}
uint8_t status = mCmt.tx(mTxBuf, len);

42
src/platformio.ini

@ -146,6 +146,48 @@ build_flags = ${env.build_flags}
monitor_filters =
esp32_exception_decoder, colorize
[env:opendtufusion-ethernet]
platform = espressif32@6.4.0
board = esp32-s3-devkitc-1
lib_deps =
khoih-prog/AsyncWebServer_ESP32_W5500
khoih-prog/AsyncUDP_ESP32_W5500
https://github.com/nrf24/RF24 @ ^1.4.8
paulstoffregen/Time @ ^1.6.1
https://github.com/bertmelis/espMqttClient#v1.5.0
bblanchon/ArduinoJson @ ^6.21.3
https://github.com/JChristensen/Timezone @ ^1.2.4
olikraus/U8g2 @ ^2.35.7
zinggjm/GxEPD2 @ ^1.5.2
upload_protocol = esp-builtin
build_flags = ${env.build_flags}
-DETHERNET
-DUSE_HSPI_FOR_EPD
-DDEF_ETH_CS_PIN=42
-DDEF_ETH_SCK_PIN=39
-DDEF_ETH_MISO_PIN=41
-DDEF_ETH_MOSI_PIN=40
-DDEF_ETH_IRQ_PIN=44
-DDEF_ETH_RST_PIN=43
-DDEF_NRF_CS_PIN=37
-DDEF_NRF_CE_PIN=38
-DDEF_NRF_IRQ_PIN=47
-DDEF_NRF_MISO_PIN=48
-DDEF_NRF_MOSI_PIN=35
-DDEF_NRF_SCLK_PIN=36
-DDEF_CMT_CSB=4
-DDEF_CMT_FCSB=21
-DDEF_CMT_IRQ=8
-DDEF_CMT_SDIO=5
-DDEF_CMT_SCLK=6
-DDEF_LED0=18
-DDEF_LED1=17
-DLED_ACTIVE_HIGH
-DARDUINO_USB_MODE=1
#-DARDUINO_USB_CDC_ON_BOOT=1
monitor_filters =
esp32_exception_decoder, colorize
[env:opendtufusion-dev]
platform = espressif32@6.4.0
board = esp32-s3-devkitc-1

137
src/plugins/Display/Display.h

@ -15,16 +15,17 @@
#include "Display_ePaper.h"
#include "Display_data.h"
template <class HMSYSTEM, class HMRADIO>
template <class HMSYSTEM, class RADIO>
class Display {
public:
Display() {
mMono = NULL;
}
void setup(IApp *app, display_t *cfg, HMSYSTEM *sys, HMRADIO *radio, uint32_t *utcTs) {
void setup(IApp *app, display_t *cfg, HMSYSTEM *sys, RADIO *hmradio, RADIO *hmsradio, uint32_t *utcTs) {
mApp = app;
mHmRadio = radio;
mHmRadio = hmradio;
mHmsRadio = hmsradio;
mCfg = cfg;
mSys = sys;
mUtcTs = utcTs;
@ -34,14 +35,14 @@ class Display {
mDisplayData.version = app->getVersion(); // version never changes, so only set once
switch (mCfg->type) {
case 0: mMono = NULL; break;
case 1: // fall-through
case 2: mMono = new DisplayMono128X64(); break;
case 3: mMono = new DisplayMono84X48(); break;
case 4: mMono = new DisplayMono128X32(); break;
case 5: mMono = new DisplayMono64X48(); break;
case 6: mMono = new DisplayMono128X64(); break;
#if defined(ESP32)
case 0: mMono = NULL; break; // None
case 1: mMono = new DisplayMono128X64(); break; // SSD1306_128X64 (0.96", 1.54")
case 2: mMono = new DisplayMono128X64(); break; // SH1106_128X64 (1.3")
case 3: mMono = new DisplayMono84X48(); break; // PCD8544_84X48 (1.6" - Nokia 5110)
case 4: mMono = new DisplayMono128X32(); break; // SSD1306_128X32 (0.91")
case 5: mMono = new DisplayMono64X48(); break; // SSD1306_64X48 (0.66" - Wemos OLED Shield)
case 6: mMono = new DisplayMono128X64(); break; // SSD1309_128X64 (2.42")
#if defined(ESP32) && !defined(ETHERNET)
case 10:
mMono = NULL; // ePaper does not use this
mRefreshCycle = 0;
@ -53,9 +54,20 @@ class Display {
default: mMono = NULL; break;
}
if(mMono) {
mMono->config(mCfg->pwrSaveAtIvOffline, mCfg->pxShift, mCfg->contrast);
mMono->config(mCfg->pwrSaveAtIvOffline, mCfg->screenSaver, mCfg->contrast);
mMono->init(mCfg->type, mCfg->rot, mCfg->disp_cs, mCfg->disp_dc, 0xff, mCfg->disp_clk, mCfg->disp_data, &mDisplayData);
}
// setup PIR pin for motion sensor
#ifdef ESP32
if ((mCfg->screenSaver == 2) && (mCfg->pirPin != DEF_PIN_OFF))
pinMode(mCfg->pirPin, INPUT);
#endif
#ifdef ESP8266
if ((mCfg->screenSaver == 2) && (mCfg->pirPin != DEF_PIN_OFF) && (mCfg->pirPin != A0))
pinMode(mCfg->pirPin, INPUT);
#endif
}
void payloadEventListener(uint8_t cmd) {
@ -64,14 +76,14 @@ class Display {
void tickerSecond() {
if (mMono != NULL)
mMono->loop(mCfg->contrast);
mMono->loop(mCfg->contrast, motionSensorActive());
if (mNewPayload || (((++mLoopCnt) % 10) == 0)) {
if (mNewPayload || (((++mLoopCnt) % 5) == 0)) {
DataScreen();
mNewPayload = false;
mLoopCnt = 0;
DataScreen();
}
#if defined(ESP32)
#if defined(ESP32) && !defined(ETHERNET)
mEpaper.tickerSecond();
#endif
}
@ -81,12 +93,13 @@ class Display {
if (mCfg->type == 0)
return;
float totalPower = 0;
float totalYieldDay = 0;
float totalYieldTotal = 0;
float totalPower = 0.0;
float totalYieldDay = 0.0;
float totalYieldTotal = 0.0;
uint8_t nrprod = 0;
uint8_t nrsleep = 0;
int8_t minQAllInv = 4;
Inverter<> *iv;
record_t<> *rec;
@ -97,33 +110,53 @@ class Display {
if (iv == NULL)
continue;
rec = iv->getRecordStruct(RealTimeRunData_Debug);
if (iv->isProducing())
if (iv->isProducing()) // also updates inverter state engine
nrprod++;
else
nrsleep++;
totalPower += iv->getChannelFieldValue(CH0, FLD_PAC, rec);
totalYieldDay += iv->getChannelFieldValue(CH0, FLD_YD, rec);
totalYieldTotal += iv->getChannelFieldValue(CH0, FLD_YT, rec);
rec = iv->getRecordStruct(RealTimeRunData_Debug);
if (iv->isAvailable()) { // consider only radio quality of inverters still communicating
int8_t maxQInv = -6;
for(uint8_t ch = 0; ch < RF_MAX_CHANNEL_ID; ch++) {
int8_t q = iv->heuristics.txRfQuality[ch];
if (q > maxQInv)
maxQInv = q;
}
if (maxQInv < minQAllInv)
minQAllInv = maxQInv;
if(allOff) {
if(iv->status != InverterStatus::OFF)
totalPower += iv->getChannelFieldValue(CH0, FLD_PAC, rec); // add only FLD_PAC from inverters still communicating
allOff = false;
}
totalYieldDay += iv->getChannelFieldValue(CH0, FLD_YD, rec);
totalYieldTotal += iv->getChannelFieldValue(CH0, FLD_YT, rec);
}
if (allOff)
minQAllInv = -6;
// prepare display data
mDisplayData.nrProducing = nrprod;
mDisplayData.nrSleeping = nrsleep;
mDisplayData.totalPower = (allOff) ? 0.0 : totalPower; // if all inverters are off, total power can't be greater than 0
mDisplayData.totalPower = totalPower;
mDisplayData.totalYieldDay = totalYieldDay;
mDisplayData.totalYieldTotal = totalYieldTotal;
mDisplayData.RadioSymbol = mHmRadio->isChipConnected();
bool nrf_en = mApp->getNrfEnabled();
bool nrf_ok = nrf_en && mHmRadio->isChipConnected();
#if defined(ESP32)
bool cmt_en = mApp->getCmtEnabled();
bool cmt_ok = cmt_en && mHmsRadio->isChipConnected();
#else
bool cmt_en = false;
bool cmt_ok = false;
#endif
mDisplayData.RadioSymbol = (nrf_ok && !cmt_en) || (cmt_ok && !nrf_en) || (nrf_ok && cmt_ok);
mDisplayData.WifiSymbol = (WiFi.status() == WL_CONNECTED);
mDisplayData.MQTTSymbol = mApp->getMqttIsConnected();
mDisplayData.RadioRSSI = (0 < mDisplayData.nrProducing) ? 0 : SCHAR_MIN; // Workaround as NRF24 has no RSSI. Could be approximated by transmisson error heuristic in the future
mDisplayData.RadioRSSI = ivQuality2RadioRSSI(minQAllInv); // Workaround as NRF24 has no RSSI. Approximation by quality levels from heuristic function
mDisplayData.WifiRSSI = (WiFi.status() == WL_CONNECTED) ? WiFi.RSSI() : SCHAR_MIN;
mDisplayData.ipAddress = WiFi.localIP();
time_t utc= mApp->getTimestamp();
@ -135,9 +168,9 @@ class Display {
if (mMono ) {
mMono->disp();
}
#if defined(ESP32)
#if defined(ESP32) && !defined(ETHERNET)
else if (mCfg->type == 10) {
mEpaper.loop(((allOff) ? 0.0 : totalPower), totalYieldDay, totalYieldTotal, nrprod);
mEpaper.loop((totalPower), totalYieldDay, totalYieldTotal, nrprod);
mRefreshCycle++;
}
@ -148,6 +181,41 @@ class Display {
#endif
}
bool motionSensorActive() {
if ((mCfg->screenSaver == 2) && (mCfg->pirPin != DEF_PIN_OFF)) {
#if defined(ESP8266)
if (mCfg->pirPin == A0)
return((analogRead(A0) >= 512));
else
return(digitalRead(mCfg->pirPin));
#elif defined(ESP32)
return(digitalRead(mCfg->pirPin));
#endif
}
else
return(false);
}
// approximate RSSI in dB by invQuality levels from heuristic function (very unscientific but better than nothing :-) )
int8_t ivQuality2RadioRSSI(int8_t invQuality) {
int8_t pseudoRSSIdB;
switch(invQuality) {
case 4: pseudoRSSIdB = -55; break;
case 3:
case 2:
case 1: pseudoRSSIdB = -65; break;
case 0:
case -1:
case -2: pseudoRSSIdB = -75; break;
case -3:
case -4:
case -5: pseudoRSSIdB = -85; break;
case -6:
default: pseudoRSSIdB = -95; break;
}
return (pseudoRSSIdB);
}
// private member variables
IApp *mApp;
DisplayData mDisplayData;
@ -156,10 +224,11 @@ class Display {
uint32_t *mUtcTs;
display_t *mCfg;
HMSYSTEM *mSys;
HMRADIO *mHmRadio;
RADIO *mHmRadio;
RADIO *mHmsRadio;
uint16_t mRefreshCycle;
#if defined(ESP32)
#if defined(ESP32) && !defined(ETHERNET)
DisplayEPaper mEpaper;
#endif
DisplayMono *mMono;

77
src/plugins/Display/Display_Mono.h

@ -18,16 +18,49 @@
#endif
#include "../../utils/helper.h"
#include "Display_data.h"
#include "../../utils/dbg.h"
class DisplayMono {
public:
DisplayMono() {};
virtual void init(uint8_t type, uint8_t rot, uint8_t cs, uint8_t dc, uint8_t reset, uint8_t clock, uint8_t data, DisplayData *displayData) = 0;
virtual void config(bool enPowerSave, bool enScreenSaver, uint8_t lum) = 0;
virtual void loop(uint8_t lum) = 0;
virtual void config(bool enPowerSave, uint8_t screenSaver, uint8_t lum) = 0;
virtual void disp(void) = 0;
// Common loop function, manages display on/off functions for powersave and screensaver with motionsensor
// can be overridden by subclasses
virtual void loop(uint8_t lum, bool motion) {
bool dispConditions = (!mEnPowerSave || (mDisplayData->nrProducing > 0)) &&
((mScreenSaver != 2) || motion); // screensaver 2 .. motionsensor
if (mDisplayActive) {
if (!dispConditions) {
if ((millis() - mStarttime) > DISP_DEFAULT_TIMEOUT * 1000ul) { // switch display off after timeout
mDisplayActive = false;
mDisplay->setPowerSave(true);
DBGPRINTLN("**** Display off ****");
}
}
else
mStarttime = millis(); // keep display on
}
else {
if (dispConditions) {
mDisplayActive = true; // switch display on
mStarttime = millis();
mDisplay->setPowerSave(false);
DBGPRINTLN("**** Display on ****");
}
}
if(mLuminance != lum) {
mLuminance = lum;
mDisplay->setContrast(mLuminance);
}
}
protected:
U8G2* mDisplay;
DisplayData *mDisplayData;
@ -36,17 +69,18 @@ class DisplayMono {
uint16_t mDispWidth;
uint16_t mDispHeight;
bool mEnPowerSave, mEnScreenSaver;
bool mEnPowerSave;
uint8_t mScreenSaver = 1; // 0 .. off; 1 .. pixelShift; 2 .. motionsensor
uint8_t mLuminance;
uint8_t mLoopCnt;
uint8_t mLineXOffsets[5] = {};
uint8_t mLineYOffsets[5] = {};
uint16_t mDispY;
uint8_t mExtra;
uint16_t mTimeout;
int8_t mPixelshift=0;
uint32_t mStarttime = millis();
bool mDisplayActive = true; // always start with display on
char mFmtText[DISP_FMT_TEXT_LEN];
// Common initialization function to be called by subclasses
@ -55,11 +89,17 @@ class DisplayMono {
mType = type;
mDisplayData = displayData;
mDisplay->begin();
mDisplay->setPowerSave(false); // always start with display on
mDisplay->setContrast(mLuminance);
mDisplay->clearBuffer();
mDispWidth = mDisplay->getDisplayWidth();
mDispHeight = mDisplay->getDisplayHeight();
}
void calcPixelShift(int range) {
int8_t mod = (millis() / 10000) % ((range >> 1) << 2);
mPixelshift = mScreenSaver == 1 ? ((mod < range) ? mod - (range >> 1) : -(mod - range - (range >> 1) + 1)) : 0;
}
};
/* adapted 5x8 Font for low-res displays with symbols
@ -74,8 +114,8 @@ Symbols:
\x87 ... moon
\x88 ... calendar/day
\x89 ... MQTT */
const uint8_t u8g2_font_5x8_symbols_ahoy[1052] U8G2_FONT_SECTION("u8g2_font_5x8_symbols_ahoy") =
"j\0\3\2\4\4\3\4\5\10\10\0\377\6\377\6\0\1\61\2b\4\3 \5\0\304\11!\7a\306"
const uint8_t u8g2_font_5x8_symbols_ahoy[1049] U8G2_FONT_SECTION("u8g2_font_5x8_symbols_ahoy") =
"j\0\3\2\4\4\3\4\5\10\10\0\377\6\377\6\0\1\61\2b\4\0 \5\0\304\11!\7a\306"
"\212!\11\42\7\63\335\212\304\22#\16u\304\232R\222\14JePJI\2$\14u\304\252l\251m"
"I\262E\0%\10S\315\212(\351\24&\13t\304\232(i\252\64%\1'\6\61\336\212\1(\7b"
"\305\32\245))\11b\305\212(\251(\0*\13T\304\212(Q\206D\211\2+\12U\304\252\60\32\244"
@ -105,9 +145,9 @@ const uint8_t u8g2_font_5x8_symbols_ahoy[1052] U8G2_FONT_SECTION("u8g2_font_5x8_
"\0z\11D\304\212!*\15\1{\12t\304*%L\304(\24|\6a\306\212\3}\13t\304\12\61"
"\12\225\60\221\0~\10$\344\232DI\0\5\0\304\12\200\13u\274\212K\242T\266\260\4\201\14f"
"D\233!\11#-\312!\11\202\15hD<\65\12\243,\214\302$\16\203\15w<\214C\22F\71\220"
"\26\207A\204\16\205\274\212,)%Y\230%QR\13\205\17\206<\213\60\31\22\311\66D\245!\11\3"
"\206\20\210<\254\342\20]\302(L\246C\30E\0\207\15wD\334X\25\267\341\20\15\21\0\210\16w"
"<\214\203RQ\25I\212\324a\20\211\15f\304\213)\213\244,\222\222\245\0\0\0\0";
"\26\207A\204\13u\274\212\244\232t\313\241\10\205\17\206<\213\60\31\22\311\66D\245!\11\3\206\20\210"
"<\254\342\20]\302(L\246C\30E\0\207\15wD\334X\25\267\341\20\15\21\0\210\16w<\214\203"
"RQ\25I\212\324a\20\211\15f\304\213)\213\244,\222\222\245\0\0\0\0";
const uint8_t u8g2_font_ncenB08_symbols8_ahoy[173] U8G2_FONT_SECTION("u8g2_font_ncenB08_symbols8_ahoy") =
@ -118,12 +158,11 @@ const uint8_t u8g2_font_ncenB08_symbols8_ahoy[173] U8G2_FONT_SECTION("u8g2_font_
"Q\4H\14w\307\215Uq\33\16\321\20\1I\21\227\305\311\222aP\245H\221\244H\212\324a\20J"
"\5\0\275\0K\5\0\315\0\0\0\0";
const uint8_t u8g2_font_ncenB10_symbols10_ahoy[207] U8G2_FONT_SECTION("u8g2_font_ncenB10_symbols10_ahoy") =
"\13\0\3\2\4\4\2\2\5\13\13\0\0\13\0\13\0\0\0\0\0\0\266A\15\267\212q\220\42\251\322"
const uint8_t u8g2_font_ncenB10_symbols10_ahoy[217] U8G2_FONT_SECTION("u8g2_font_ncenB10_symbols10_ahoy") =
"\13\0\3\2\4\4\2\2\5\13\13\0\0\13\0\13\0\0\0\0\0\0\300A\15\267\212q\220\42\251\322"
"\266\306\275\1B\20\230\236\65da\22Ima\250F\71\254\1C\23\272\272\251\3Q\32\366Q\212\243"
"\70\212\243\70\311\221\0D\20\271\252\361\242F:\242#: {\36\16\1E\22\267\212\361\222\14I\242"
"\14\332\232\216[RJ\232\12F\25\250\233\221\14I\61I\206$\252%J\250Fa\224%J\71G\30"
"\273\312W\316r`T\262DJ\303\64L#%K\304\35\310\342,\3H\27\272\272\217\344P\16\351\210"
"\16\354\300<\244C\70,\303 \16!\0I\24\271\252\241\34\336\1-\223\64-\323\62-\323\62\35x"
"\10J\5\0\232\1K\5\0\232\1\0\0\0";
"\70\212\243\70\311\221\0D\20\271\252\361\242F:\242#: {\36\16\1E\17\267\212\221\264\3Q\35"
"\332\321\34\316\341\14F\25\250\233\221\14I\61I\206$\252%J\250Fa\224%J\71G\30\273\312W"
"\316r`T\262DJ\303\64L#%K\304\35\310\342,\3H\27\272\272\217\344P\16\351\210\16\354\300"
"<\244C\70,\303 \16!\0I\24\271\252\241\34\336\1-\223\64-\323\62-\323\62\35x\10J\22"
"\210\232\61Hi\64Di\64DI\226$KeiK\5\0\212\1\0\0\0";

36
src/plugins/Display/Display_Mono_128X32.h

@ -9,17 +9,12 @@
class DisplayMono128X32 : public DisplayMono {
public:
DisplayMono128X32() : DisplayMono() {
mEnPowerSave = true;
mEnScreenSaver = true;
mLuminance = 60;
mExtra = 0;
mDispY = 0;
mTimeout = DISP_DEFAULT_TIMEOUT; // interval at which to power save (milliseconds)
}
void config(bool enPowerSave, bool enScreenSaver, uint8_t lum) {
void config(bool enPowerSave, uint8_t screenSaver, uint8_t lum) {
mEnPowerSave = enPowerSave;
mEnScreenSaver = enScreenSaver;
mScreenSaver = screenSaver;
mLuminance = lum;
}
@ -33,28 +28,13 @@ class DisplayMono128X32 : public DisplayMono {
mDisplay->sendBuffer();
}
void loop(uint8_t lum) {
if (mEnPowerSave) {
if (mTimeout != 0)
mTimeout--;
}
if(mLuminance != lum) {
mLuminance = lum;
mDisplay->setContrast(mLuminance);
}
}
void disp(void) {
mDisplay->clearBuffer();
// set Contrast of the Display to raise the lifetime
if (3 != mType)
mDisplay->setContrast(mLuminance);
// calculate current pixelshift for pixelshift screensaver
calcPixelShift(pixelShiftRange);
if ((mDisplayData->totalPower > 0) && (mDisplayData->nrProducing > 0)) {
mTimeout = DISP_DEFAULT_TIMEOUT;
mDisplay->setPowerSave(false);
if (mDisplayData->totalPower > 999)
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%2.2f kW", (mDisplayData->totalPower / 1000));
else
@ -63,9 +43,6 @@ class DisplayMono128X32 : public DisplayMono {
printText(mFmtText, 0);
} else {
printText("offline", 0);
// check if it's time to enter power saving mode
if (mTimeout == 0)
mDisplay->setPowerSave(mEnPowerSave);
}
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "today: %4.0f Wh", mDisplayData->totalYieldDay);
@ -85,11 +62,12 @@ class DisplayMono128X32 : public DisplayMono {
mDisplay->sendBuffer();
mDispY = 0;
mExtra++;
}
private:
const uint8_t pixelShiftRange = 7; // number of pixels to shift from left to right (centered -> must be odd!)
void calcLinePositions() {
uint8_t yOff[] = {0, 0};
for (uint8_t i = 0; i < 4; i++) {
@ -131,7 +109,7 @@ class DisplayMono128X32 : public DisplayMono {
void printText(const char *text, uint8_t line) {
setFont(line);
uint8_t dispX = mLineXOffsets[line] + ((mEnScreenSaver) ? (mExtra % 7) : 0);
uint8_t dispX = mLineXOffsets[line] + pixelShiftRange / 2 + mPixelshift;
if (isTwoRowLine(line)) {
String stringText = String(text);

230
src/plugins/Display/Display_Mono_128X64.h

@ -9,16 +9,12 @@
class DisplayMono128X64 : public DisplayMono {
public:
DisplayMono128X64() : DisplayMono() {
mEnPowerSave = true;
mEnScreenSaver = true;
mLuminance = 60;
mDispY = 0;
mTimeout = DISP_DEFAULT_TIMEOUT; // interval at which to power save (milliseconds)
mExtra = 0;
}
void config(bool enPowerSave, bool enScreenSaver, uint8_t lum) {
void config(bool enPowerSave, uint8_t screenSaver, uint8_t lum) {
mEnPowerSave = enPowerSave;
mEnScreenSaver = enScreenSaver;
mScreenSaver = screenSaver;
mLuminance = lum;
}
@ -37,95 +33,197 @@ class DisplayMono128X64 : public DisplayMono {
break;
}
calcLinePositions();
printText("Ahoy!", 0, 35);
printText("ahoydtu.de", 2, 20);
printText(mDisplayData->version, 3, 46);
mDisplay->sendBuffer();
}
void loop(uint8_t lum) {
if (mEnPowerSave) {
if (mTimeout != 0)
mTimeout--;
}
if(mLuminance != lum) {
mLuminance = lum;
mDisplay->setContrast(mLuminance);
}
printText("Ahoy!", l_Ahoy, 0xff);
printText("ahoydtu.de", l_Website, 0xff);
printText(mDisplayData->version, l_Version, 0xff);
mDisplay->sendBuffer();
}
void disp(void) {
mDisplay->clearBuffer();
uint8_t pos, sun_pos, moon_pos;
// set Contrast of the Display to raise the lifetime
mDisplay->setContrast(mLuminance);
if ((mDisplayData->totalPower > 0) && (mDisplayData->nrProducing > 0)) {
mTimeout = DISP_DEFAULT_TIMEOUT;
mDisplay->setPowerSave(false);
mDisplay->clearBuffer();
// Layout-Test
/*
mDisplayData->nrSleeping = 10;
mDisplayData->nrProducing = 10;
mDisplayData->totalPower = 54321.9; // W
mDisplayData->totalYieldDay = 4321.9; // Wh
mDisplayData->totalYieldTotal = 4321.9; // kWh
mDisplay->drawPixel(0, 0);
mDisplay->drawPixel(mDispWidth-1, 0);
mDisplay->drawPixel(0, mDispHeight-1);
mDisplay->drawPixel(mDispWidth-1, mDispHeight-1);
*/
// calculate current pixelshift for pixelshift screensaver
calcPixelShift(pixelShiftRange);
// print total power
if (mDisplayData->nrProducing > 0) {
if (mDisplayData->totalPower > 999)
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%2.2f kW", (mDisplayData->totalPower / 1000));
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%.1f kW", (mDisplayData->totalPower / 1000.0));
else
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%3.0f W", mDisplayData->totalPower);
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%.0f W", mDisplayData->totalPower);
printText(mFmtText, 0);
printText(mFmtText, l_TotalPower, 0xff);
} else {
printText("offline", 0, 25);
// check if it's time to enter power saving mode
if (mTimeout == 0)
mDisplay->setPowerSave(mEnPowerSave);
printText("offline", l_TotalPower, 0xff);
}
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "today: %4.0f Wh", mDisplayData->totalYieldDay);
printText(mFmtText, 1);
// print Date and time
if (0 != mDisplayData->utcTs)
printText(ah::getDateTimeStrShort(gTimezone.toLocal(mDisplayData->utcTs)).c_str(), l_Time, 0xff);
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "total: %.1f kWh", mDisplayData->totalYieldTotal);
printText(mFmtText, 2);
// dynamic status bar, alternatively:
// print ip address
if (!(mExtra % 5) && (mDisplayData->ipAddress)) {
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%s", (mDisplayData->ipAddress).toString().c_str());
printText(mFmtText, l_Status, 0xff);
}
// print status of inverters
else {
sun_pos = -1;
moon_pos = -1;
setLineFont(l_Status);
if (0 == mDisplayData->nrSleeping + mDisplayData->nrProducing)
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "no inverter");
else if (0 == mDisplayData->nrSleeping) {
snprintf(mFmtText, DISP_FMT_TEXT_LEN, " ");
sun_pos = 0;
}
else if (0 == mDisplayData->nrProducing) {
snprintf(mFmtText, DISP_FMT_TEXT_LEN, " ");
moon_pos = 0;
}
else {
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%2d", mDisplayData->nrProducing);
sun_pos = mDisplay->getStrWidth(mFmtText) + 1;
snprintf(mFmtText+2, DISP_FMT_TEXT_LEN, " %2d", mDisplayData->nrSleeping);
moon_pos = mDisplay->getStrWidth(mFmtText) + 1;
snprintf(mFmtText+7, DISP_FMT_TEXT_LEN, " ");
}
printText(mFmtText, l_Status, 0xff);
pos = (mDispWidth - mDisplay->getStrWidth(mFmtText)) / 2;
mDisplay->setFont(u8g2_font_ncenB08_symbols8_ahoy);
if (sun_pos!=-1)
mDisplay->drawStr(pos + sun_pos + mPixelshift, mLineYOffsets[l_Status], "G"); // sun symbol
if (moon_pos!=-1)
mDisplay->drawStr(pos + moon_pos + mPixelshift, mLineYOffsets[l_Status], "H"); // moon symbol
}
// print yields
mDisplay->setFont(u8g2_font_ncenB10_symbols10_ahoy);
mDisplay->drawStr(16 + mPixelshift, mLineYOffsets[l_YieldDay], "I"); // day symbol
mDisplay->drawStr(16 + mPixelshift, mLineYOffsets[l_YieldTotal], "D"); // total symbol
if (mDisplayData->totalYieldDay > 999.0)
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%.1f kWh", mDisplayData->totalYieldDay / 1000.0);
else
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%.0f Wh", mDisplayData->totalYieldDay);
printText(mFmtText, l_YieldDay, 0xff);
if (mDisplayData->totalYieldTotal > 999.0)
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%.1f MWh", mDisplayData->totalYieldTotal / 1000.0);
else
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%.1f kWh", mDisplayData->totalYieldTotal);
printText(mFmtText, l_YieldTotal, 0xff);
// draw dynamic RSSI bars
int xoffs;
if (mScreenSaver == 1) // shrink screenwidth for pixelshift screensaver
xoffs = pixelShiftRange/2;
else
xoffs = 0;
int rssi_bar_height = 9;
for (int i = 0; i < 4; i++) {
int radio_rssi_threshold = -60 - i * 10;
int wifi_rssi_threshold = -60 - i * 10;
if (mDisplayData->RadioRSSI > radio_rssi_threshold)
mDisplay->drawBox(xoffs + mPixelshift, 8 + (rssi_bar_height + 1) * i, 4 - i, rssi_bar_height);
if (mDisplayData->WifiRSSI > wifi_rssi_threshold)
mDisplay->drawBox(mDispWidth - 4 - xoffs + mPixelshift + i, 8 + (rssi_bar_height + 1) * i, 4 - i, rssi_bar_height);
}
// draw dynamic antenna and WiFi symbols
mDisplay->setFont(u8g2_font_ncenB10_symbols10_ahoy);
char sym[]=" ";
sym[0] = mDisplayData->RadioSymbol?'A':'E'; // NRF
mDisplay->drawStr(xoffs + mPixelshift, mLineYOffsets[l_RSSI], sym);
if (mDisplayData->MQTTSymbol)
sym[0] = 'J'; // MQTT
else
sym[0] = mDisplayData->WifiSymbol?'B':'F'; // Wifi
mDisplay->drawStr(mDispWidth - mDisplay->getStrWidth(sym) - xoffs + mPixelshift, mLineYOffsets[l_RSSI], sym);
mDisplay->sendBuffer();
IPAddress ip = WiFi.localIP();
if (!(mExtra % 10) && (ip))
printText(ip.toString().c_str(), 3);
else if (!(mExtra % 5)) {
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%d Inverter on", mDisplayData->nrProducing);
printText(mFmtText, 3);
} else if (0 != mDisplayData->utcTs)
printText(ah::getDateTimeStr(gTimezone.toLocal(mDisplayData->utcTs)).c_str(), 3);
mDisplay->sendBuffer();
mDispY = 0;
mExtra++;
}
private:
enum _dispLine {
// start page
l_Website = 0,
l_Ahoy = 2,
l_Version = 4,
// run page
l_Time = 0,
l_Status = 1,
l_TotalPower = 2,
l_YieldDay = 3,
l_YieldTotal = 4,
// run page - rssi bar symbols
l_RSSI = 4,
// End
l_MAX_LINES = 5,
};
const uint8_t pixelShiftRange = 11; // number of pixels to shift from left to right (centered -> must be odd!)
void calcLinePositions() {
uint8_t yOff = 0;
for (uint8_t i = 0; i < 4; i++) {
setFont(i);
yOff += (mDisplay->getMaxCharHeight());
uint8_t i = 0;
uint8_t asc, dsc;
do {
setLineFont(i);
asc = mDisplay->getAscent();
yOff += asc;
mLineYOffsets[i] = yOff;
}
dsc = mDisplay->getDescent();
yOff -= dsc;
if (l_Time==i) // prevent time and status line to touch
yOff+=1; // -> one pixels space
i++;
} while(l_MAX_LINES>i);
}
inline void setFont(uint8_t line) {
switch (line) {
case 0:
inline void setLineFont(uint8_t line) {
if ((line == l_TotalPower) ||
(line == l_Ahoy))
mDisplay->setFont(u8g2_font_ncenB14_tr);
break;
case 3:
mDisplay->setFont(u8g2_font_5x8_symbols_ahoy);
break;
default:
else if ((line == l_YieldDay) ||
(line == l_YieldTotal))
// mDisplay->setFont(u8g2_font_5x8_symbols_ahoy);
mDisplay->setFont(u8g2_font_ncenB10_tr);
break;
}
else
mDisplay->setFont(u8g2_font_ncenB08_tr);
}
void printText(const char *text, uint8_t line, uint8_t dispX = 5) {
setFont(line);
dispX += (mEnScreenSaver) ? (mExtra % 7) : 0;
void printText(const char *text, uint8_t line, uint8_t col=0) {
uint8_t dispX;
setLineFont(line);
if (0xff == col)
dispX = (mDispWidth - mDisplay->getStrWidth(text)) / 2; // center text
else
dispX = col;
dispX += mPixelshift;
mDisplay->drawStr(dispX, mLineYOffsets[line], text);
}
};

38
src/plugins/Display/Display_Mono_64X48.h

@ -9,17 +9,12 @@
class DisplayMono64X48 : public DisplayMono {
public:
DisplayMono64X48() : DisplayMono() {
mEnPowerSave = true;
mEnScreenSaver = false;
mLuminance = 20;
mExtra = 0;
mDispY = 0;
mTimeout = DISP_DEFAULT_TIMEOUT; // interval at which to power save (milliseconds)
}
void config(bool enPowerSave, bool enScreenSaver, uint8_t lum) {
void config(bool enPowerSave, uint8_t screenSaver, uint8_t lum) {
mEnPowerSave = enPowerSave;
mEnScreenSaver = enScreenSaver;
mScreenSaver = screenSaver;
mLuminance = lum;
}
@ -27,6 +22,7 @@ class DisplayMono64X48 : public DisplayMono {
u8g2_cb_t *rot = (u8g2_cb_t *)((rotation != 0x00) ? U8G2_R2 : U8G2_R0);
// Wemos OLed Shield is not defined in u8 lib -> use nearest compatible
monoInit(new U8G2_SSD1306_64X48_ER_F_HW_I2C(rot, reset, clock, data), type, displayData);
calcLinePositions();
printText("Ahoy!", 0);
printText("ahoydtu.de", 1);
@ -34,28 +30,13 @@ class DisplayMono64X48 : public DisplayMono {
mDisplay->sendBuffer();
}
void loop(uint8_t lum) {
if (mEnPowerSave) {
if (mTimeout != 0)
mTimeout--;
}
if(mLuminance != lum) {
mLuminance = lum;
mDisplay->setContrast(mLuminance);
}
}
void disp(void) {
mDisplay->clearBuffer();
// set Contrast of the Display to raise the lifetime
mDisplay->setContrast(mLuminance);
// calculate current pixelshift for pixelshift screensaver
calcPixelShift(pixelShiftRange);
if ((mDisplayData->totalPower > 0) && (mDisplayData->nrProducing > 0)) {
mTimeout = DISP_DEFAULT_TIMEOUT;
mDisplay->setPowerSave(false);
if (mDisplayData->totalPower > 999)
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%2.2f kW", (mDisplayData->totalPower / 1000));
else
@ -64,9 +45,6 @@ class DisplayMono64X48 : public DisplayMono {
printText(mFmtText, 0);
} else {
printText("offline", 0);
// check if it's time to enter power saving mode
if (mTimeout == 0)
mDisplay->setPowerSave(mEnPowerSave);
}
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "D: %4.0f Wh", mDisplayData->totalYieldDay);
@ -90,6 +68,8 @@ class DisplayMono64X48 : public DisplayMono {
}
private:
const uint8_t pixelShiftRange = 4; // number of pixels to shift from left to right
void calcLinePositions() {
uint8_t yOff = 0;
for (uint8_t i = 0; i < 4; i++) {
@ -118,8 +98,8 @@ class DisplayMono64X48 : public DisplayMono {
}
void printText(const char *text, uint8_t line) {
uint8_t dispX = 0; //small display, use all we have
dispX += (mEnScreenSaver) ? (mExtra % 4) : 0;
uint8_t dispX = mLineXOffsets[line] + pixelShiftRange/2 + mPixelshift;
setFont(line);
mDisplay->drawStr(dispX, mLineYOffsets[line], text);
}

83
src/plugins/Display/Display_Mono_84X48.h

@ -10,17 +10,12 @@
class DisplayMono84X48 : public DisplayMono {
public:
DisplayMono84X48() : DisplayMono() {
mEnPowerSave = true;
mEnScreenSaver = true;
mLuminance = 140;
mExtra = 0;
mDispY = 0;
mTimeout = DISP_DEFAULT_TIMEOUT; // interval at which to power save (milliseconds)
}
void config(bool enPowerSave, bool enScreenSaver, uint8_t lum) {
void config(bool enPowerSave, uint8_t screenSaver, uint8_t lum) {
mEnPowerSave = enPowerSave;
mEnScreenSaver = enScreenSaver;
mScreenSaver = screenSaver;
mLuminance = lum;
}
@ -34,49 +29,32 @@ class DisplayMono84X48 : public DisplayMono {
mDisplay->sendBuffer();
}
void loop(uint8_t lum) {
if (mEnPowerSave) {
if (mTimeout != 0)
mTimeout--;
}
if(mLuminance != lum) {
mLuminance = lum;
mDisplay->setContrast(mLuminance);
}
}
void disp(void) {
// Test
mDisplay->clearBuffer();
// Layout-Test
/*
mDisplayData->nrSleeping = 10;
mDisplayData->nrProducing = 10;
mDisplayData->totalPower = 12345.67;
mDisplayData->totalYieldDay = 12345.67;
mDisplayData->totalYieldTotal = 1234;
mDisplayData->utcTs += 1000000;
mDisplayData->totalPower = 111.91; // W
mDisplayData->totalYieldDay = 54321.9; // Wh
mDisplayData->totalYieldTotal = 654321.9; // kWh
mDisplay->drawPixel(0, 0);
mDisplay->drawPixel(mDispWidth-1, 0);
mDisplay->drawPixel(0, mDispHeight-1);
mDisplay->drawPixel(mDispWidth-1, mDispHeight-1);
*/
mDisplay->clearBuffer();
// print total power
if (mDisplayData->nrProducing > 0) {
mTimeout = DISP_DEFAULT_TIMEOUT;
mDisplay->setPowerSave(false);
if (mDisplayData->totalPower > 9999)
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%.2fkW", (mDisplayData->totalPower / 1000)); // forgo spacing between value and SI unit in favor of second position after decimal point
else if (mDisplayData->totalPower > 999)
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%.2f kW", (mDisplayData->totalPower / 1000));
if (mDisplayData->totalPower > 999)
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%.1f kW", (mDisplayData->totalPower / 1000));
else
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%.1f W", mDisplayData->totalPower);
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%.0f W", mDisplayData->totalPower);
printText(mFmtText, l_TotalPower, 0xff);
} else {
printText("offline", l_TotalPower, 0xff);
// check if it's time to enter power saving mode
if (mTimeout == 0)
mDisplay->setPowerSave(mEnPowerSave);
}
// print Date and time
@ -91,23 +69,32 @@ class DisplayMono84X48 : public DisplayMono {
}
// print status of inverters
else {
if (0 == mDisplayData->nrSleeping)
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "\x86");
if (0 == mDisplayData->nrSleeping + mDisplayData->nrProducing)
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "no inverter");
else if (0 == mDisplayData->nrSleeping)
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "\x86"); // sun symbol
else if (0 == mDisplayData->nrProducing)
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "\x87");
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "\x87"); // moon symbol
else
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%d\x86 %d\x87", mDisplayData->nrProducing, mDisplayData->nrSleeping);
setLineFont(l_Status);
printText(mFmtText, l_Status, (mDispWidth - mDisplay->getStrWidth(mFmtText)) / 2);
printText(mFmtText, l_Status, 0xff);
}
// print yields
printText("\x88", l_YieldDay, 11); // day symbol
printText("\x83", l_YieldTotal, 11); // total symbol
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%7.0f Wh", mDisplayData->totalYieldDay);
printText(mFmtText, l_YieldDay, 18);
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%7.1f kWh", mDisplayData->totalYieldTotal);
printText(mFmtText, l_YieldTotal, 18);
printText("\x88", l_YieldDay, 10); // day symbol
printText("\x83", l_YieldTotal, 10); // total symbol
if (mDisplayData->totalYieldDay > 999.0)
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%.1f kWh", mDisplayData->totalYieldDay / 1000.0);
else
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%.0f Wh", mDisplayData->totalYieldDay);
printText(mFmtText, l_YieldDay, 0xff);
if (mDisplayData->totalYieldTotal > 999.0)
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%.1f MWh", mDisplayData->totalYieldTotal / 1000.0);
else
snprintf(mFmtText, DISP_FMT_TEXT_LEN, "%.1f kWh", mDisplayData->totalYieldTotal);
printText(mFmtText, l_YieldTotal, 0xff);
// draw dynamic Nokia RSSI bars
int rssi_bar_height = 7;

4
src/plugins/Display/Display_data.h

@ -6,8 +6,8 @@
struct DisplayData {
const char *version=nullptr;
float totalPower=0.0f; // indicate current power (W)
float totalYieldDay=0.0f; // indicate day yield (W)
float totalYieldTotal=0.0f; // indicate total yield (W)
float totalYieldDay=0.0f; // indicate day yield (Wh)
float totalYieldTotal=0.0f; // indicate total yield (kWh)
uint32_t utcTs=0; // indicate absolute timestamp (utc unix time). 0 = time is not synchonized
uint8_t nrProducing=0; // indicate number of producing inverters
uint8_t nrSleeping=0; // indicate number of sleeping inverters

4
src/publisher/pubMqtt.h

@ -245,7 +245,11 @@ class PubMqtt {
publish(subtopics[MQTT_VERSION], mVersion, true);
publish(subtopics[MQTT_DEVICE], mDevName, true);
#if defined(ETHERNET)
publish(subtopics[MQTT_IP_ADDR], ETH.localIP().toString().c_str(), true);
#else
publish(subtopics[MQTT_IP_ADDR], WiFi.localIP().toString().c_str(), true);
#endif
tickerMinute();
publish(mLwtTopic, mqttStr[MQTT_STR_LWT_CONN], true, false);

11
src/utils/helper.cpp

@ -70,6 +70,17 @@ namespace ah {
return String(str);
}
String getTimeStrMs(uint64_t t) {
char str[13];
if(0 == t)
sprintf(str, "n/a");
else {
t = (t + (millis() % 1000)) / 1000;
sprintf(str, "%02d:%02d:%02d.%03d", hour(t), minute(t), second(t), millis() % 1000);
}
return String(str);
}
uint64_t Serial2u64(const char *val) {
char tmp[3];
uint64_t ret = 0ULL;

1
src/utils/helper.h

@ -44,6 +44,7 @@ namespace ah {
String getDateTimeStrShort(time_t t);
String getDateTimeStrFile(time_t t);
String getTimeStr(time_t t);
String getTimeStrMs(uint64_t t);
uint64_t Serial2u64(const char *val);
void dumpBuf(uint8_t buf[], uint8_t len, uint8_t firstRepl = 0, uint8_t lastRepl = 0);
}

11
src/utils/scheduler.h

@ -34,6 +34,7 @@ namespace ah {
void setup(bool directStart) {
mUptime = 0;
mTimestamp = (directStart) ? 1 : 0;
mTsMillis = 0;
mMax = 0;
mPrevMillis = millis();
resetTicker();
@ -59,8 +60,10 @@ namespace ah {
}
mUptime += mDiffSeconds;
if(0 != mTimestamp)
if(0 != mTimestamp) {
mTimestamp += mDiffSeconds;
mTsMillis = mMillis % 1000;
}
checkTicker();
}
@ -77,6 +80,7 @@ namespace ah {
virtual void setTimestamp(uint32_t ts) {
mTimestamp = ts;
mTsMillis = millis() % 1000;
}
bool resetEveryById(uint8_t id) {
@ -90,10 +94,6 @@ namespace ah {
return mUptime;
}
uint32_t getTimestamp(void) {
return mTimestamp;
}
inline void resetTicker(void) {
for (uint8_t i = 0; i < MAX_NUM_TICKER; i++)
mTickerInUse[i] = false;
@ -118,6 +118,7 @@ namespace ah {
protected:
uint32_t mTimestamp;
uint32_t mUptime;
uint16_t mTsMillis;
private:
inline uint8_t addTicker(scdCb c, uint32_t timeout, uint32_t reload, bool isTimestamp, const char *name) {

9
src/utils/spiPatcher.cpp

@ -0,0 +1,9 @@
//-----------------------------------------------------------------------------
// 2023 Ahoy, https://www.mikrocontroller.net/topic/525778
// Creative Commons - http://creativecommons.org/licenses/by-nc-sa/3.0/de/
//-----------------------------------------------------------------------------
#if defined(ESP32)
#include "spiPatcher.h"
SpiPatcher *SpiPatcher::mInstance = nullptr;
#endif

88
src/utils/spiPatcher.h

@ -0,0 +1,88 @@
//-----------------------------------------------------------------------------
// 2023 Ahoy, https://www.mikrocontroller.net/topic/525778
// Creative Commons - http://creativecommons.org/licenses/by-nc-sa/3.0/de/
//-----------------------------------------------------------------------------
#ifndef __SPI_PATCHER_H__
#define __SPI_PATCHER_H__
#pragma once
#if defined(ESP32)
#include "spiPatcherHandle.h"
#include <driver/spi_master.h>
#include <freertos/semphr.h>
class SpiPatcher {
protected:
SpiPatcher(spi_host_device_t dev) :
mHostDevice(dev), mCurHandle(nullptr) {
// Use binary semaphore instead of mutex for performance reasons
mutex = xSemaphoreCreateBinaryStatic(&mutex_buffer);
xSemaphoreGive(mutex);
spi_bus_config_t buscfg = {
.mosi_io_num = -1,
.miso_io_num = -1,
.sclk_io_num = -1,
.quadwp_io_num = -1,
.quadhd_io_num = -1,
.data4_io_num = -1,
.data5_io_num = -1,
.data6_io_num = -1,
.data7_io_num = -1,
.max_transfer_sz = SOC_SPI_MAXIMUM_BUFFER_SIZE,
.flags = 0,
.intr_flags = 0
};
ESP_ERROR_CHECK(spi_bus_initialize(mHostDevice, &buscfg, SPI_DMA_DISABLED));
}
public:
SpiPatcher(SpiPatcher &other) = delete;
void operator=(const SpiPatcher &) = delete;
static SpiPatcher* getInstance(spi_host_device_t dev) {
if(nullptr == mInstance)
mInstance = new SpiPatcher(dev);
return mInstance;
}
~SpiPatcher() { vSemaphoreDelete(mutex); }
spi_host_device_t getDevice() {
return mHostDevice;
}
inline void request(SpiPatcherHandle* handle) {
xSemaphoreTake(mutex, portMAX_DELAY);
if (mCurHandle != handle) {
if (mCurHandle) {
mCurHandle->unpatch();
}
mCurHandle = handle;
if (mCurHandle) {
mCurHandle->patch();
}
}
}
inline void release() {
xSemaphoreGive(mutex);
}
protected:
static SpiPatcher *mInstance;
private:
const spi_host_device_t mHostDevice;
SpiPatcherHandle* mCurHandle;
SemaphoreHandle_t mutex;
StaticSemaphore_t mutex_buffer;
};
#endif /*ESP32*/
#endif /*__SPI_PATCHER_H__*/

17
src/utils/spiPatcherHandle.h

@ -0,0 +1,17 @@
//-----------------------------------------------------------------------------
// 2023 Ahoy, https://www.mikrocontroller.net/topic/525778
// Creative Commons - http://creativecommons.org/licenses/by-nc-sa/3.0/de/
//-----------------------------------------------------------------------------
#ifndef __SPI_PATCHER_HANDLE_H__
#define __SPI_PATCHER_HANDLE_H__
#pragma once
class SpiPatcherHandle {
public:
virtual ~SpiPatcherHandle() {}
virtual void patch() = 0;
virtual void unpatch() = 0;
};
#endif /*__SPI_PATCHER_HANDLE_H__*/

34
src/web/RestApi.h

@ -47,12 +47,12 @@ class RestApi {
mSys = sys;
mRadioNrf = (HmRadio<>*)mApp->getRadioObj(true);
#if defined(ESP32)
mRadioCmt = (CmtRadio<esp32_3wSpi>*)mApp->getRadioObj(false);
mRadioCmt = (CmtRadio<>*)mApp->getRadioObj(false);
#endif
mConfig = config;
mSrv->on("/api", HTTP_GET, std::bind(&RestApi::onApi, this, std::placeholders::_1));
mSrv->on("/api", HTTP_POST, std::bind(&RestApi::onApiPost, this, std::placeholders::_1)).onBody(
std::bind(&RestApi::onApiPostBody, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5));
mSrv->on("/api", HTTP_GET, std::bind(&RestApi::onApi, this, std::placeholders::_1));
mSrv->on("/get_setup", HTTP_GET, std::bind(&RestApi::onDwnldSetup, this, std::placeholders::_1));
}
@ -72,6 +72,8 @@ class RestApi {
private:
void onApi(AsyncWebServerRequest *request) {
DPRINTLN(DBG_VERBOSE, String("onApi: ") + String((uint16_t)request->method())); // 1 == Get, 3 == POST
mHeapFree = ESP.getFreeHeap();
#ifndef ESP32
mHeapFreeBlk = ESP.getMaxFreeBlockSize();
@ -120,6 +122,12 @@ class RestApi {
void onApiPost(AsyncWebServerRequest *request) {
DPRINTLN(DBG_VERBOSE, "onApiPost");
#if defined(ETHERNET)
// workaround for AsyncWebServer_ESP32_W5500, because it can't distinguish
// between HTTP_GET and HTTP_POST if both are registered
if(request->method() == HTTP_GET)
onApi(request);
#endif
}
void onApiPostBody(AsyncWebServerRequest *request, uint8_t *data, size_t len, size_t index, size_t total) {
@ -381,7 +389,7 @@ class RestApi {
obj2[F("ch_max_pwr")][j] = iv->config->chMaxPwr[j];
}
}
obj[F("interval")] = String(mConfig->nrf.sendInterval);
obj[F("interval")] = String(mConfig->inst.sendInterval);
obj[F("max_num_inverters")] = MAX_NUM_INVERTERS;
obj[F("rstMid")] = (bool)mConfig->inst.rstYieldMidNight;
obj[F("rstNotAvail")] = (bool)mConfig->inst.rstValsNotAvail;
@ -389,6 +397,7 @@ class RestApi {
obj[F("strtWthtTm")] = (bool)mConfig->inst.startWithoutTime;
obj[F("rstMaxMid")] = (bool)mConfig->inst.rstMaxValsMidNight;
obj[F("yldEff")] = mConfig->inst.yieldEffiency;
obj[F("gap")] = mConfig->inst.gapMs;
}
void getInverter(JsonObject obj, uint8_t id) {
@ -563,21 +572,27 @@ class RestApi {
void getRadioCmtInfo(JsonObject obj) {
obj[F("en")] = (bool) mConfig->cmt.enabled;
obj[F("isconnected")] = mRadioCmt->isConnected();
if(mConfig->cmt.enabled) {
obj[F("isconnected")] = mRadioCmt->isChipConnected();
obj[F("sn")] = String(mRadioCmt->getDTUSn(), HEX);
}
}
#endif
void getRadioNrf(JsonObject obj) {
obj[F("en")] = (bool) mConfig->nrf.enabled;
if(mConfig->nrf.enabled) {
obj[F("isconnected")] = mRadioNrf->isChipConnected();
obj[F("dataRate")] = mRadioNrf->getDataRate();
//obj[F("isPVariant")] = mRadioNrf->isPVariant();
obj[F("sn")] = String(mRadioNrf->getDTUSn(), HEX);
}
}
void getSerial(JsonObject obj) {
obj[F("show_live_data")] = mConfig->serial.showIv;
obj[F("debug")] = mConfig->serial.debug;
obj[F("priv")] = mConfig->serial.privacyLog;
obj[F("wholeTrace")] = mConfig->serial.printWholeTrace;
}
void getStaticIp(JsonObject obj) {
@ -592,7 +607,7 @@ class RestApi {
void getDisplay(JsonObject obj) {
obj[F("disp_typ")] = (uint8_t)mConfig->plugin.display.type;
obj[F("disp_pwr")] = (bool)mConfig->plugin.display.pwrSaveAtIvOffline;
obj[F("disp_pxshift")] = (bool)mConfig->plugin.display.pxShift;
obj[F("disp_screensaver")] = (uint8_t)mConfig->plugin.display.screenSaver;
obj[F("disp_rot")] = (uint8_t)mConfig->plugin.display.rot;
obj[F("disp_cont")] = (uint8_t)mConfig->plugin.display.contrast;
obj[F("disp_clk")] = (mConfig->plugin.display.type == 0) ? DEF_PIN_OFF : mConfig->plugin.display.disp_clk;
@ -601,6 +616,7 @@ class RestApi {
obj[F("disp_dc")] = (mConfig->plugin.display.type < 3) ? DEF_PIN_OFF : mConfig->plugin.display.disp_dc;
obj[F("disp_rst")] = (mConfig->plugin.display.type < 3) ? DEF_PIN_OFF : mConfig->plugin.display.disp_reset;
obj[F("disp_bsy")] = (mConfig->plugin.display.type < 10) ? DEF_PIN_OFF : mConfig->plugin.display.disp_busy;
obj[F("pir_pin")] = mConfig->plugin.display.pirPin;
}
void getMqttInfo(JsonObject obj) {
@ -643,8 +659,6 @@ class RestApi {
JsonArray warn = obj.createNestedArray(F("warnings"));
if(!mRadioNrf->isChipConnected() && mConfig->nrf.enabled)
warn.add(F("your NRF24 module can't be reached, check the wiring, pinout and enable"));
else if(!mRadioNrf->isPVariant() && mConfig->nrf.enabled)
warn.add(F("your NRF24 module isn't a plus version(+), maybe incompatible"));
if(!mApp->getSettingsValid())
warn.add(F("your settings are invalid"));
if(mApp->getRebootRequestState())
@ -682,7 +696,7 @@ class RestApi {
void getLive(AsyncWebServerRequest *request, JsonObject obj) {
getGeneric(request, obj.createNestedObject(F("generic")));
obj[F("refresh")] = mConfig->nrf.sendInterval;
obj[F("refresh")] = mConfig->inst.sendInterval;
for (uint8_t fld = 0; fld < sizeof(acList); fld++) {
obj[F("ch0_fld_units")][fld] = String(units[fieldUnits[acList[fld]]]);
@ -788,7 +802,7 @@ class RestApi {
HMSYSTEM *mSys;
HmRadio<> *mRadioNrf;
#if defined(ESP32)
CmtRadio<esp32_3wSpi> *mRadioCmt;
CmtRadio<> *mRadioCmt;
#endif
AsyncWebServer *mSrv;
settings_t *mConfig;

20
src/web/html/serial.html

@ -17,6 +17,7 @@
<div class="col-6 col-sm-4 a-r">
<input type="button" value="clear" class="btn" id="clear"/>
<input type="button" value="autoscroll" class="btn" id="scroll"/>
<input type="button" value="copy" class="btn" id="copy"/>
</div>
</div>
</div>
@ -63,6 +64,25 @@
mAutoScroll = !mAutoScroll;
this.value = (mAutoScroll) ? "autoscroll" : "manual scroll";
});
document.getElementById("copy").addEventListener("click", function() {
if (window.clipboardData && window.clipboardData.setData) {
return window.clipboardData.setData("Text", text);
} else if (document.queryCommandSupported && document.queryCommandSupported("copy")) {
var ta = document.createElement("textarea");
ta.textContent = con.value;
ta.style.position = "fixed"; // Prevent scrolling to bottom of page in Microsoft Edge.
document.body.appendChild(ta);
ta.select();
try {
return document.execCommand("copy"); // Security exception may be thrown by some browsers.
} catch (ex) {
alert("Copy to clipboard failed" + ex);
} finally {
document.body.removeChild(ta);
alert("Copied to clipboard");
}
}
});
if (!!window.EventSource) {
var source = new EventSource('/events');

89
src/web/html/setup.html

@ -53,6 +53,10 @@
<div class="col-8 col-sm-3">Privacy Mode</div>
<div class="col-4 col-sm-9"><input type="checkbox" name="priv"/></div>
</div>
<div class="row mb-3">
<div class="col-8 col-sm-3">Print whole traces in Log</div>
<div class="col-4 col-sm-9"><input type="checkbox" name="wholeTrace"/></div>
</div>
</fieldset>
</div>
@ -148,6 +152,10 @@
<div class="col-8 my-2">Interval [s]</div>
<div class="col-4"><input type="number" name="invInterval" title="Invalid input"/></div>
</div>
<div class="row mb-3">
<div class="col-8 my-2">Inverter Gap [ms]</div>
<div class="col-4"><input type="number" name="invGap" title="Invalid input"/></div>
</div>
<div class="row mb-3">
<div class="col-8 mb-2">Reset values and YieldDay at midnight</div>
<div class="col-4"><input type="checkbox" name="invRstMid"/></div>
@ -169,7 +177,7 @@
<div class="col-4"><input type="checkbox" name="strtWthtTm"/></div>
</div>
<div class="row mb-3">
<div class="col-8">Yield Efficiency (should be between 0.95 and 0.96)</div>
<div class="col-8">Yield Efficiency (Standard 1.0)</div>
<div class="col-4"><input type="number" name="yldEff" step="any"/></div>
</div>
</fieldset>
@ -282,16 +290,14 @@
<div class="col-8 col-sm-3">Turn off while inverters are offline</div>
<div class="col-4 col-sm-9"><input type="checkbox" name="disp_pwr"/></div>
</div>
<div class="row mb-3">
<div class="col-8 col-sm-3">Enable Screensaver (pixel shifting, OLED only)</div>
<div class="col-4 col-sm-9"><input type="checkbox" name="disp_pxshift"/></div>
</div>
<div id="screenSaver"></div>
<div class="row mb-3">
<div class="col-12 col-sm-3 my-2">Luminance</div>
<div class="col-12 col-sm-9"><input type="number" name="disp_cont" min="0" max="255"></select></div>
</div>
<p class="des">Pinout</p>
<div id="dispPins"></div>
<div id="pirPin"></div>
</fieldset>
</div>
@ -491,7 +497,8 @@
});
for(var i = 0; i < 31; i++) {
esp32cmtPa.push([i, String(i-10) + " dBm"]);
if(i < 29)
}
for(var i = 12; i < 41; i++) {
esp32cmtFreq.push([i, freqFmt.format(860 + i*0.25) + " MHz"]);
}
/*ENDIF_ESP32*/
@ -617,7 +624,7 @@
}
function ivGlob(obj) {
for(var i of [["invInterval", "interval"], ["yldEff", "yldEff"]])
for(var i of [["invInterval", "interval"], ["yldEff", "yldEff"], ["invGap", "gap"]])
document.getElementsByName(i[0])[0].value = obj[i[1]];
for(var i of ["Mid", "ComStop", "NotAvail", "MaxMid"])
document.getElementsByName("invRst"+i)[0].checked = obj["rst" + i];
@ -844,10 +851,10 @@
getAjax("/api/setup", cb, "POST", JSON.stringify(o));
}
function cb(obj) {
function cb(obj2) {
var e = document.getElementById("res");
if(!obj.success)
e.innerHTML = "error: " + obj.error;
if(!obj2.success)
e.innerHTML = "error: " + obj2.error;
else {
modalClose();
getAjax("/api/inverter/list", parseIv);
@ -986,22 +993,22 @@
/*ENDIF_ESP32*/
function parseSerial(obj) {
for(var i of [["serEn", "show_live_data"], ["serDbg", "debug"], ["priv", "priv"]])
for(var i of [["serEn", "show_live_data"], ["serDbg", "debug"], ["priv", "priv"], ["wholeTrace", "wholeTrace"]])
document.getElementsByName(i[0])[0].checked = obj[i[1]];
}
function parseDisplay(obj, type, system) {
for(var i of ["disp_pwr", "disp_pxshift"])
for(var i of ["disp_pwr"])
document.getElementsByName(i)[0].checked = obj[i];
var e = document.getElementById("dispPins");
var dpins_elem = document.getElementById("dispPins");
//KEEP this order !!!
var pins = [['clock', 'disp_clk'], ['data', 'disp_data'], ['cs', 'disp_cs'], ['dc', 'disp_dc'], ['reset', 'disp_rst']];
/*IF_ESP32*/
pins.push(['busy', 'disp_bsy']);
/*ENDIF_ESP32*/
for(p of pins) {
e.append(
dpins_elem.append(
ml("div", {class: "row mb-3", id: "row_" + p[1]}, [
ml("div", {class: "col-12 col-sm-3 my-2"}, p[0].toUpperCase()),
ml("div", {class: "col-12 col-sm-9"},
@ -1010,23 +1017,24 @@
])
);
}
// keep display types grouped
var opts = [[0, "None"], [2, "SH1106 1.3\" 128X64"], [5, "SSD1306 0.66\" 64X48 (Wemos OLED Shield)"], [4, "SSD1306 0.91\" 128X32"], [1, "SSD1306 0.96\" 128X64"], [6, "SSD1309 2.42\" 128X64"], [3, "Nokia5110"]];
var opts = [[0, "None"],
[2, "SH1106 128x64 (1.3\")"],
[5, "SSD1306 64x48 (0.66\" Wemos OLED Shield)"],
[4, "SSD1306 128x32 (0.91\")"],
[1, "SSD1306 128x64 (0.96\", 1.54\")"],
[6, "SSD1309 128X64 (2.42\")"],
[3, "PCD8544 84X48 (1.6\" Nokia 5110)"]];
/*IF_ESP32*/
opts.push([10, "ePaper"]);
/*ENDIF_ESP32*/
var dispType = sel("disp_typ", opts, obj["disp_typ"]);
var dtype_sel = sel("disp_typ", opts, obj["disp_typ"]);
document.getElementById("dispType").append(
ml("div", {class: "row mb-3"}, [
ml("div", {class: "col-12 col-sm-3 my-2"}, "Type"),
ml("div", {class: "col-12 col-sm-9"}, dispType)
ml("div", {class: "col-12 col-sm-9"}, dtype_sel)
])
);
dispType.addEventListener('change', (e) => {
hideDispPins(pins, parseInt(e.target.value))
});
opts = [[0, "0&deg;"], [2, "180&deg;"]];
/*IF_ESP32*/
opts.push([1, "90&deg;"]);
@ -1039,7 +1047,35 @@
])
);
var opts1 = [[0, "off"], [1, "pixel shift"], [2, "motion sensor"]];
var screensaver_sel = sel("disp_screensaver", opts1, obj["disp_screensaver"]);
screensaver_sel.id = 'disp_screensaver';
document.getElementById("screenSaver").append(
ml("div", {class: "row mb-3"}, [
ml("div", {class: "col-12 col-sm-3 my-2"}, "Screensaver (OLED only)"),
ml("div", {class: "col-12 col-sm-9"}, screensaver_sel)
])
);
var esp8266pirpins = [[255, "off / default"],
[17, "A0"]];
document.getElementById("pirPin").append(
ml("div", {class: "row mb-3"}, [
ml("div", {class: "col-12 col-sm-3 my-2"}, "PIR sensor"),
ml("div", {class: "col-12 col-sm-9"}, sel("pir_pin", ("ESP8266" == type) ? esp8266pirpins : ("ESP32-S3" == system["chip_model"]) ? esp32s3pins : esp32pins, obj["pir_pin"]))
])
);
document.getElementsByName("disp_cont")[0].value = obj["disp_cont"];
dtype_sel.addEventListener('change', function(e) {
hideDispPins(pins, parseInt(e.target.value))
});
document.getElementById("disp_screensaver").addEventListener('change', function(e) {
hideDispPins(pins, parseInt(dtype_sel.value))
});
hideDispPins(pins, obj.disp_typ);
}
@ -1066,6 +1102,15 @@
cl.add("hide");
}
}
var screenSaver = document.getElementById("disp_screensaver").value;
if (2==screenSaver) { // show pir pin only for motion screensaver
setHide("pirPin", false);
}
else { // no pir pin for all others
setHide("pirPin", true);
}
}
function tick() {

8
src/web/html/system.html

@ -50,7 +50,8 @@
if(obj.radioNrf.en) {
lines = [
tr("NRF24L01", badge(obj.radioNrf.isconnected, ((obj.radioNrf.isconnected) ? "" : "not ") + "connected")),
tr("NRF24 Data Rate", dr[obj.radioNrf.dataRate] + "bps")
tr("NRF24 Data Rate", dr[obj.radioNrf.dataRate] + "bps"),
tr("DTU Radio ID", obj.radioNrf.sn)
];
} else
lines = [tr("NRF24L01", badge(false, "not enabled"))];
@ -64,7 +65,10 @@
/*IF_ESP32*/
if(obj.radioCmt.en) {
cmt = [tr("CMT2300A", badge(obj.radioCmt.isconnected, ((obj.radioCmt.isconnected) ? "" : "not ") + "connected"))];
cmt = [
tr("CMT2300A", badge(obj.radioCmt.isconnected, ((obj.radioCmt.isconnected) ? "" : "not ") + "connected")),
tr("DTU Radio ID", obj.radioCmt.sn)
];
} else
cmt = [tr("CMT2300A", badge(false, "not enabled"))];

5
src/web/html/update.html

@ -12,9 +12,12 @@
<legend class="des">Select firmware file (*.bin)</legend>
<form id="form" method="POST" action="/update" enctype="multipart/form-data" accept-charset="utf-8">
<input type="file" name="update">
<input type="button" class="btn" value="Update" onclick="hide()">
<input type="button" class="btn my-4" value="Update" onclick="hide()">
</form>
</fieldset>
<div class="row mt-4">
<a href="https://fw.ahoydtu.de" target="_blank">Download latest Release and Development versions<a/>
</div>
</div>
</div>
{#HTML_FOOTER}

3
src/web/html/visualization.html

@ -109,7 +109,6 @@
if(0 != obj.max_pwr)
pwrLimit += ", " + Math.round(obj.max_pwr * obj.power_limit_read / 100) + "W";
}
return ml("div", {class: "row mt-2"},
ml("div", {class: "col"}, [
ml("div", {class: "p-2 " + clh},
@ -124,7 +123,7 @@
ml("div", {class: "col a-c"}, ml("span", { class: "pointer", onclick: function() {
getAjax("/api/inverter/alarm/" + obj.id, parseIvAlarm);
}}, ("Alarms: " + obj.alarm_cnt))),
ml("div", {class: "col a-r mx-2 mx-md-1"}, String(obj.ch[0][5]) + t.innerText)
ml("div", {class: "col a-r mx-2 mx-md-1"}, String(obj.ch[0][5].toFixed(1)) + t.innerText)
])
),
ml("div", {class: "p-2 " + clbg}, [

25
src/web/web.h

@ -82,9 +82,9 @@ class Web {
mWeb.on("/metrics", HTTP_ANY, std::bind(&Web::showMetrics, this, std::placeholders::_1));
#endif
mWeb.on("/update", HTTP_GET, std::bind(&Web::onUpdate, this, std::placeholders::_1));
mWeb.on("/update", HTTP_POST, std::bind(&Web::showUpdate, this, std::placeholders::_1),
std::bind(&Web::showUpdate2, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6));
mWeb.on("/update", HTTP_GET, std::bind(&Web::onUpdate, this, std::placeholders::_1));
mWeb.on("/upload", HTTP_POST, std::bind(&Web::onUpload, this, std::placeholders::_1),
std::bind(&Web::onUpload2, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6));
mWeb.on("/serial", HTTP_GET, std::bind(&Web::onSerial, this, std::placeholders::_1));
@ -208,10 +208,11 @@ class Web {
msg.replace("\r\n", "<rn>");
if (mSerialAddTime) {
if ((9 + mSerialBufFill) < WEB_SERIAL_BUF_SIZE) {
if ((13 + mSerialBufFill) < WEB_SERIAL_BUF_SIZE) {
if (mApp->getTimestamp() > 0) {
strncpy(&mSerialBuf[mSerialBufFill], mApp->getTimeStr(mApp->getTimezoneOffset()).c_str(), 9);
mSerialBufFill += 9;
strncpy(&mSerialBuf[mSerialBufFill], ah::getTimeStrMs(mApp->getTimestampMs() + mApp->getTimezoneOffset() * 1000).c_str(), 12);
mSerialBuf[mSerialBufFill+12] = ' ';
mSerialBufFill += 13;
}
} else {
mSerialBufFill = 0;
@ -272,6 +273,13 @@ class Web {
}
void showUpdate(AsyncWebServerRequest *request) {
#if defined(ETHERNET)
// workaround for AsyncWebServer_ESP32_W5500, because it can't distinguish
// between HTTP_GET and HTTP_POST if both are registered
if(request->method() == HTTP_GET)
onUpdate(request);
#endif
bool reboot = (!Update.hasError());
String html = F("<!doctype html><html><head><title>Update</title><meta http-equiv=\"refresh\" content=\"20; URL=/\"></head><body>Update: ");
@ -488,13 +496,14 @@ class Web {
ah::ip2Arr(mConfig->sys.ip.gateway, buf);
if (request->arg("invInterval") != "")
mConfig->nrf.sendInterval = request->arg("invInterval").toInt();
mConfig->inst.sendInterval = request->arg("invInterval").toInt();
mConfig->inst.rstYieldMidNight = (request->arg("invRstMid") == "on");
mConfig->inst.rstValsCommStop = (request->arg("invRstComStop") == "on");
mConfig->inst.rstValsNotAvail = (request->arg("invRstNotAvail") == "on");
mConfig->inst.startWithoutTime = (request->arg("strtWthtTm") == "on");
mConfig->inst.rstMaxValsMidNight = (request->arg("invRstMaxMid") == "on");
mConfig->inst.yieldEffiency = (request->arg("yldEff")).toFloat();
mConfig->inst.gapMs = (request->arg("invGap")).toInt();
// pinout
@ -520,8 +529,6 @@ class Web {
}
mConfig->nrf.enabled = (request->arg("nrfEnable") == "on");
// cmt
mConfig->cmt.enabled = (request->arg("cmtEnable") == "on");
// ntp
@ -585,11 +592,12 @@ class Web {
// serial console
mConfig->serial.debug = (request->arg("serDbg") == "on");
mConfig->serial.privacyLog = (request->arg("priv") == "on");
mConfig->serial.printWholeTrace = (request->arg("wholeTrace") == "on");
mConfig->serial.showIv = (request->arg("serEn") == "on");
// display
mConfig->plugin.display.pwrSaveAtIvOffline = (request->arg("disp_pwr") == "on");
mConfig->plugin.display.pxShift = (request->arg("disp_pxshift") == "on");
mConfig->plugin.display.screenSaver = request->arg("disp_screensaver").toInt();
mConfig->plugin.display.rot = request->arg("disp_rot").toInt();
mConfig->plugin.display.type = request->arg("disp_typ").toInt();
mConfig->plugin.display.contrast = (mConfig->plugin.display.type == 0) ? 60 : request->arg("disp_cont").toInt();
@ -599,6 +607,7 @@ class Web {
mConfig->plugin.display.disp_reset = (mConfig->plugin.display.type < 3) ? DEF_PIN_OFF : request->arg("disp_rst").toInt();
mConfig->plugin.display.disp_dc = (mConfig->plugin.display.type < 3) ? DEF_PIN_OFF : request->arg("disp_dc").toInt();
mConfig->plugin.display.disp_busy = (mConfig->plugin.display.type < 10) ? DEF_PIN_OFF : request->arg("disp_bsy").toInt();
mConfig->plugin.display.pirPin = request->arg("pir_pin").toInt();
mApp->saveSettings((request->arg("reboot") == "on"));

19
src/wifi/ahoywifi.cpp

@ -10,6 +10,12 @@
#endif
#include "ahoywifi.h"
#if defined(ESP32)
#include <ESPmDNS.h>
#else
#include <ESP8266mDNS.h>
#endif
// NTP CONFIG
#define NTP_PACKET_SIZE 48
@ -83,6 +89,9 @@ void ahoywifi::tickWifiLoop() {
if (mGotDisconnect) {
mStaConn = RESET;
}
#if !defined(ESP32)
MDNS.update();
#endif
return;
case IN_AP_MODE:
if (WiFi.softAPgetStationNum() == 0) {
@ -180,6 +189,15 @@ void ahoywifi::tickWifiLoop() {
mAppWifiCb(true);
mGotDisconnect = false;
mStaConn = IN_STA_MODE;
if (!MDNS.begin(mConfig->sys.deviceName)) {
DPRINTLN(DBG_ERROR, F("Error setting up MDNS responder!"));
} else {
DBGPRINT(F("[WiFi] mDNS established: "));
DBGPRINT(mConfig->sys.deviceName);
DBGPRINTLN(F(".local"));
}
break;
case RESET:
mGotDisconnect = false;
@ -245,7 +263,6 @@ void ahoywifi::setupStation(void) {
WiFi.hostname(mConfig->sys.deviceName);
WiFi.mode(WIFI_AP_STA);
DBGPRINT(F("connect to network '"));
DBGPRINT(mConfig->sys.stationSsid);
DBGPRINTLN(F("' ..."));

11
tools/fonts/u8g2_font_5x8_symbols_ahoy.bdf

@ -1243,16 +1243,15 @@ STARTCHAR 132
ENCODING 132
SWIDTH 360 0
DWIDTH 5 0
BBX 5 8 0 -1
BBX 5 7 0 -1
BITMAP
88
50
A8
00
A8
50
20
00
20
50
50
88
ENDCHAR
STARTCHAR 133
ENCODING 133

10
tools/fonts/u8g2_font_5x8_symbols_ahoy.c_

@ -4,8 +4,8 @@
Glyphs: 106/106
BBX Build Mode: 0
*/
const uint8_t u8g2_font_5x8_symbols_ahoy[1052] U8G2_FONT_SECTION("u8g2_font_5x8_symbols_ahoy") =
"j\0\3\2\4\4\3\4\5\10\10\0\377\6\377\6\0\1\61\2b\4\3 \5\0\304\11!\7a\306"
const uint8_t u8g2_font_5x8_symbols_ahoy[1049] U8G2_FONT_SECTION("u8g2_font_5x8_symbols_ahoy") =
"j\0\3\2\4\4\3\4\5\10\10\0\377\6\377\6\0\1\61\2b\4\0 \5\0\304\11!\7a\306"
"\212!\11\42\7\63\335\212\304\22#\16u\304\232R\222\14JePJI\2$\14u\304\252l\251m"
"I\262E\0%\10S\315\212(\351\24&\13t\304\232(i\252\64%\1'\6\61\336\212\1(\7b"
"\305\32\245))\11b\305\212(\251(\0*\13T\304\212(Q\206D\211\2+\12U\304\252\60\32\244"
@ -35,6 +35,6 @@ const uint8_t u8g2_font_5x8_symbols_ahoy[1052] U8G2_FONT_SECTION("u8g2_font_5x8_
"\0z\11D\304\212!*\15\1{\12t\304*%L\304(\24|\6a\306\212\3}\13t\304\12\61"
"\12\225\60\221\0~\10$\344\232DI\0\5\0\304\12\200\13u\274\212K\242T\266\260\4\201\14f"
"D\233!\11#-\312!\11\202\15hD<\65\12\243,\214\302$\16\203\15w<\214C\22F\71\220"
"\26\207A\204\16\205\274\212,)%Y\230%QR\13\205\17\206<\213\60\31\22\311\66D\245!\11\3"
"\206\20\210<\254\342\20]\302(L\246C\30E\0\207\15wD\334X\25\267\341\20\15\21\0\210\16w"
"<\214\203RQ\25I\212\324a\20\211\15f\304\213)\213\244,\222\222\245\0\0\0\0";
"\26\207A\204\13u\274\212\244\232t\313\241\10\205\17\206<\213\60\31\22\311\66D\245!\11\3\206\20\210"
"<\254\342\20]\302(L\246C\30E\0\207\15wD\334X\25\267\341\20\15\21\0\210\16w<\214\203"
"RQ\25I\212\324a\20\211\15f\304\213)\213\244,\222\222\245\0\0\0\0";

BIN
tools/fonts/u8g2_font_5x8_symbols_ahoy.fon

Binary file not shown.

32
tools/fonts/u8g2_font_ncenB10_symbols10_ahoy.bdf

@ -88,17 +88,17 @@ SWIDTH 576 0
DWIDTH 8 0
BBX 7 11 0 0
BITMAP
FE
D6
D6
7C
AA
00
92
00
38
00
10
00
10
00
10
38
38
54
54
92
ENDCHAR
STARTCHAR 070
ENCODING 70
@ -175,13 +175,21 @@ STARTCHAR 074
ENCODING 74
SWIDTH 648 0
DWIDTH 9 0
BBX 0 0 0 0
BBX 8 8 0 0
BITMAP
F9
04
F2
09
E5
15
D5
D5
ENDCHAR
STARTCHAR 075
ENCODING 75
SWIDTH 648 0
DWIDTH 9 0
SWIDTH 576 0
DWIDTH 8 0
BBX 0 0 0 0
BITMAP
ENDCHAR

14
tools/fonts/u8g2_font_ncenB10_symbols10_ahoy.c_

@ -4,11 +4,11 @@
Glyphs: 11/11
BBX Build Mode: 0
*/
const uint8_t u8g2_font_ncenB10_symbols10_ahoy[207] U8G2_FONT_SECTION("u8g2_font_ncenB10_symbols10_ahoy") =
"\13\0\3\2\4\4\2\2\5\13\13\0\0\13\0\13\0\0\0\0\0\0\266A\15\267\212q\220\42\251\322"
const uint8_t u8g2_font_ncenB10_symbols10_ahoy[217] U8G2_FONT_SECTION("u8g2_font_ncenB10_symbols10_ahoy") =
"\13\0\3\2\4\4\2\2\5\13\13\0\0\13\0\13\0\0\0\0\0\0\300A\15\267\212q\220\42\251\322"
"\266\306\275\1B\20\230\236\65da\22Ima\250F\71\254\1C\23\272\272\251\3Q\32\366Q\212\243"
"\70\212\243\70\311\221\0D\20\271\252\361\242F:\242#: {\36\16\1E\22\267\212\361\222\14I\242"
"\14\332\232\216[RJ\232\12F\25\250\233\221\14I\61I\206$\252%J\250Fa\224%J\71G\30"
"\273\312W\316r`T\262DJ\303\64L#%K\304\35\310\342,\3H\27\272\272\217\344P\16\351\210"
"\16\354\300<\244C\70,\303 \16!\0I\24\271\252\241\34\336\1-\223\64-\323\62-\323\62\35x"
"\10J\5\0\232\1K\5\0\232\1\0\0\0";
"\70\212\243\70\311\221\0D\20\271\252\361\242F:\242#: {\36\16\1E\17\267\212\221\264\3Q\35"
"\332\321\34\316\341\14F\25\250\233\221\14I\61I\206$\252%J\250Fa\224%J\71G\30\273\312W"
"\316r`T\262DJ\303\64L#%K\304\35\310\342,\3H\27\272\272\217\344P\16\351\210\16\354\300"
"<\244C\70,\303 \16!\0I\24\271\252\241\34\336\1-\223\64-\323\62-\323\62\35x\10J\22"
"\210\232\61Hi\64Di\64DI\226$KeiK\5\0\212\1\0\0\0";

BIN
tools/fonts/u8g2_font_ncenB10_symbols10_ahoy.fon

Binary file not shown.
Loading…
Cancel
Save