mirror of
https://github.com/lumapu/ahoy.git
synced 2025-05-22 13:26:10 +02:00
commit
1300f0a19e
13 changed files with 1687 additions and 1 deletions
158
tools/NRF24_SendRcv/CircularBuffer.h
Normal file
158
tools/NRF24_SendRcv/CircularBuffer.h
Normal file
|
@ -0,0 +1,158 @@
|
|||
/*
|
||||
CircularBuffer - An Arduino circular buffering library for arbitrary types.
|
||||
|
||||
Created by Ivo Pullens, Emmission, 2014 -- www.emmission.nl
|
||||
|
||||
This library is free software; you can redistribute it and/or
|
||||
modify it under the terms of the GNU Lesser General Public
|
||||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
|
||||
This library is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
||||
Lesser General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU Lesser General Public
|
||||
License along with this library; if not, write to the Free Software
|
||||
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||
*/
|
||||
|
||||
#ifndef CircularBuffer_h
|
||||
#define CircularBuffer_h
|
||||
|
||||
#ifdef ESP8266
|
||||
#define DISABLE_IRQ noInterrupts()
|
||||
#define RESTORE_IRQ interrupts()
|
||||
#else
|
||||
#define DISABLE_IRQ \
|
||||
uint8_t sreg = SREG; \
|
||||
cli();
|
||||
|
||||
#define RESTORE_IRQ \
|
||||
SREG = sreg;
|
||||
#endif
|
||||
|
||||
template <class T> class CircularBuffer
|
||||
{
|
||||
public:
|
||||
/** Constructor
|
||||
* @param buffer Preallocated buffer of at least size records.
|
||||
* @param size Number of records available in the buffer.
|
||||
*/
|
||||
CircularBuffer(T* buffer, const uint8_t size )
|
||||
: m_size(size), m_buff(buffer)
|
||||
{
|
||||
clear();
|
||||
}
|
||||
|
||||
/** Clear all entries in the circular buffer. */
|
||||
void clear(void)
|
||||
{
|
||||
m_front = 0;
|
||||
m_fill = 0;
|
||||
}
|
||||
|
||||
/** Test if the circular buffer is empty */
|
||||
inline bool empty(void) const
|
||||
{
|
||||
return !m_fill;
|
||||
}
|
||||
|
||||
/** Return the number of records stored in the buffer */
|
||||
inline uint8_t available(void) const
|
||||
{
|
||||
return m_fill;
|
||||
}
|
||||
|
||||
/** Test if the circular buffer is full */
|
||||
inline bool full(void) const
|
||||
{
|
||||
return m_fill == m_size;
|
||||
}
|
||||
|
||||
/** Aquire record on front of the buffer, for writing.
|
||||
* After filling the record, it has to be pushed to actually
|
||||
* add it to the buffer.
|
||||
* @return Pointer to record, or NULL when buffer is full.
|
||||
*/
|
||||
T* getFront(void) const
|
||||
{
|
||||
DISABLE_IRQ;
|
||||
T* f = NULL;
|
||||
if (!full())
|
||||
f = get(m_front);
|
||||
RESTORE_IRQ;
|
||||
return f;
|
||||
}
|
||||
|
||||
/** Push record to front of the buffer
|
||||
* @param record Record to push. If record was aquired previously (using getFront) its
|
||||
* data will not be copied as it is already present in the buffer.
|
||||
* @return True, when record was pushed successfully.
|
||||
*/
|
||||
bool pushFront(T* record)
|
||||
{
|
||||
bool ok = false;
|
||||
DISABLE_IRQ;
|
||||
if (!full())
|
||||
{
|
||||
T* f = get(m_front);
|
||||
if (f != record)
|
||||
*f = *record;
|
||||
m_front = (m_front+1) % m_size;
|
||||
m_fill++;
|
||||
ok = true;
|
||||
}
|
||||
RESTORE_IRQ;
|
||||
return ok;
|
||||
}
|
||||
|
||||
/** Aquire record on back of the buffer, for reading.
|
||||
* After reading the record, it has to be pop'ed to actually
|
||||
* remove it from the buffer.
|
||||
* @return Pointer to record, or NULL when buffer is empty.
|
||||
*/
|
||||
T* getBack(void) const
|
||||
{
|
||||
T* b = NULL;
|
||||
DISABLE_IRQ;
|
||||
if (!empty())
|
||||
b = get(back());
|
||||
RESTORE_IRQ;
|
||||
return b;
|
||||
}
|
||||
|
||||
/** Remove record from back of the buffer.
|
||||
* @return True, when record was pop'ed successfully.
|
||||
*/
|
||||
bool popBack(void)
|
||||
{
|
||||
bool ok = false;
|
||||
DISABLE_IRQ;
|
||||
if (!empty())
|
||||
{
|
||||
m_fill--;
|
||||
ok = true;
|
||||
}
|
||||
RESTORE_IRQ;
|
||||
return ok;
|
||||
}
|
||||
|
||||
protected:
|
||||
inline T * get(const uint8_t idx) const
|
||||
{
|
||||
return &(m_buff[idx]);
|
||||
}
|
||||
inline uint8_t back(void) const
|
||||
{
|
||||
return (m_front - m_fill + m_size) % m_size;
|
||||
}
|
||||
|
||||
const uint8_t m_size; // Total number of records that can be stored in the buffer.
|
||||
T* const m_buff; // Ptr to buffer holding all records.
|
||||
volatile uint8_t m_front; // Index of front element (not pushed yet).
|
||||
volatile uint8_t m_fill; // Amount of records currently pushed.
|
||||
};
|
||||
|
||||
#endif // CircularBuffer_h
|
23
tools/NRF24_SendRcv/Debug.h
Normal file
23
tools/NRF24_SendRcv/Debug.h
Normal file
|
@ -0,0 +1,23 @@
|
|||
#ifndef __DEBUG_H
|
||||
|
||||
#define __DEBUG_H
|
||||
|
||||
#ifdef DEBUG
|
||||
#define DEBUG_OUT Serial
|
||||
#else
|
||||
//---
|
||||
// disable Serial DEBUG output
|
||||
#define DEBUG_OUT DummySerial
|
||||
static class {
|
||||
public:
|
||||
void begin(...) {}
|
||||
void print(...) {}
|
||||
void println(...) {}
|
||||
void flush() {}
|
||||
bool available() { return false;}
|
||||
int readBytes(...) { return 0;}
|
||||
int printf (...) {return 0;}
|
||||
} DummySerial;
|
||||
#endif
|
||||
|
||||
#endif
|
129
tools/NRF24_SendRcv/ModWebserver.h
Normal file
129
tools/NRF24_SendRcv/ModWebserver.h
Normal file
|
@ -0,0 +1,129 @@
|
|||
// ################# WebServer #################
|
||||
|
||||
#ifndef __MODWEBSERVER_H
|
||||
#define __MODWEBSERVER_H
|
||||
#define MODWEBSERVER
|
||||
|
||||
#include <ESP8266WebServer.h>
|
||||
#include "Debug.h"
|
||||
#include "Settings.h"
|
||||
|
||||
ESP8266WebServer server (WEBSERVER_PORT);
|
||||
|
||||
|
||||
void returnOK () {
|
||||
//--------------
|
||||
server.send(200, F("text/plain"), "");
|
||||
}
|
||||
|
||||
|
||||
void returnFail(String msg) {
|
||||
//-------------------------
|
||||
server.send(500, F("text/plain"), msg + "\r\n");
|
||||
}
|
||||
|
||||
void handleHelp () {
|
||||
//-----------------
|
||||
String out = "<html>";
|
||||
out += "<body><h2>Hilfe</h2>";
|
||||
out += "<br><br><table>";
|
||||
out += "<tr><td>/</td><td>zeigt alle Messwerte in einer Tabelle; refresh alle 10 Sekunden</td></tr>";
|
||||
out += "<tr><td>/data</td><td>zum Abruf der Messwerte in der Form Name=wert</td></tr>";
|
||||
out += "<tr><td>:{port+1}/update</td><td>OTA</td></tr>";
|
||||
out += "<tr><td>/reboot</td><td>startet neu</td></tr>";
|
||||
out += "</table></body></html>";
|
||||
server.send (200, "text/html", out);
|
||||
}
|
||||
|
||||
|
||||
void handleReboot () {
|
||||
//-------------------
|
||||
returnOK ();
|
||||
ESP.reset();
|
||||
}
|
||||
|
||||
|
||||
void handleRoot() {
|
||||
//----------------
|
||||
String out = "<html><head><meta http-equiv=\"refresh\" content=\"10\":URL=\"" + server.uri() + "\"></head>";
|
||||
out += "<body>";
|
||||
out += "<h2>Hoymiles Micro-Inverter HM-600</h2>";
|
||||
out += "<br><br><table border='1'>";
|
||||
out += "<tr><th>Kanal</th><th>Wert</th></tr>";
|
||||
for (byte i = 0; i < ANZAHL_VALUES; i++) {
|
||||
out += "<tr><td>" + String(getChannelName(i)) + "</td>";
|
||||
out += "<td>" + String(VALUES[i]) + "</td></tr>";
|
||||
}
|
||||
out += "</table>";
|
||||
out += "</body></html>";
|
||||
server.send (200, "text/html", out);
|
||||
//DEBUG_OUT.println (out);
|
||||
}
|
||||
|
||||
|
||||
void handleData () {
|
||||
//-----------------
|
||||
String out = "";
|
||||
for (int i = 0; i < ANZAHL_VALUES; i++) {
|
||||
out += String(getChannelName(i)) + '=' + String (VALUES[i]) + '\n';
|
||||
}
|
||||
server.send(200, "text/plain", out);
|
||||
}
|
||||
|
||||
|
||||
void handleNotFound() {
|
||||
//--------------------
|
||||
String message = "URI: ";
|
||||
message += server.uri();
|
||||
message += "\nMethod: ";
|
||||
message += (server.method() == HTTP_GET) ? "GET" : "POST";
|
||||
message += "\nArguments: ";
|
||||
message += server.args();
|
||||
message += "\n";
|
||||
for (uint8_t i = 0; i < server.args(); i++) {
|
||||
message += " NAME:" + server.argName(i) + "\n VALUE:" + server.arg(i) + "\n";
|
||||
}
|
||||
server.send(404, "text/plain", message);
|
||||
}
|
||||
|
||||
|
||||
void setupWebServer (void) {
|
||||
//-------------------------
|
||||
server.on("/", handleRoot);
|
||||
server.on("/reboot", handleReboot);
|
||||
server.on("/data", handleData);
|
||||
server.on("/help", handleHelp);
|
||||
//server.onNotFound(handleNotFound); wegen Spiffs-Dateimanager
|
||||
|
||||
server.begin();
|
||||
DEBUG_OUT.println ("[HTTP] installed");
|
||||
}
|
||||
|
||||
void webserverHandle() {
|
||||
//====================
|
||||
server.handleClient();
|
||||
}
|
||||
|
||||
|
||||
// ################# OTA #################
|
||||
|
||||
#ifdef WITH_OTA
|
||||
#include <ESP8266HTTPUpdateServer.h>
|
||||
|
||||
ESP8266WebServer httpUpdateServer (UPDATESERVER_PORT);
|
||||
ESP8266HTTPUpdateServer httpUpdater;
|
||||
|
||||
void setupUpdateByOTA () {
|
||||
//------------------------
|
||||
httpUpdater.setup (&httpUpdateServer, UPDATESERVER_DIR, UPDATESERVER_USER, UPDATESERVER_PW);
|
||||
httpUpdateServer.begin();
|
||||
DEBUG_OUT.println (F("[OTA] installed"));
|
||||
}
|
||||
|
||||
void checkUpdateByOTA() {
|
||||
//---------------------
|
||||
httpUpdateServer.handleClient();
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
597
tools/NRF24_SendRcv/NRF24_SendRcv.ino
Normal file
597
tools/NRF24_SendRcv/NRF24_SendRcv.ino
Normal file
|
@ -0,0 +1,597 @@
|
|||
#include <Arduino.h>
|
||||
#include <SPI.h>
|
||||
#include "CircularBuffer.h"
|
||||
#include <RF24.h>
|
||||
#include <RF24_config.h>
|
||||
#include "hm_crc.h"
|
||||
#include "hm_packets.h"
|
||||
|
||||
#include "Settings.h" // Header für Einstellungen
|
||||
|
||||
#include "Debug.h"
|
||||
|
||||
#ifdef ESP8266
|
||||
#define DISABLE_EINT noInterrupts()
|
||||
#define ENABLE_EINT interrupts()
|
||||
#else // für AVR z.B. ProMini oder Nano
|
||||
#define DISABLE_EINT EIMSK = 0x00
|
||||
#define ENABLE_EINT EIMSK = 0x01
|
||||
#endif
|
||||
|
||||
|
||||
#define RF_MAX_ADDR_WIDTH (5)
|
||||
#define MAX_RF_PAYLOAD_SIZE (32)
|
||||
|
||||
#ifdef ESP8266
|
||||
#define PACKET_BUFFER_SIZE (30)
|
||||
#else
|
||||
#define PACKET_BUFFER_SIZE (20)
|
||||
#endif
|
||||
|
||||
// Startup defaults until user reconfigures it
|
||||
#define DEFAULT_RECV_CHANNEL (3) // 3 = Default channel for Hoymiles
|
||||
//#define DEFAULT_SEND_CHANNEL (75) // 40 = Default channel for Hoymiles, 61
|
||||
#define DEFAULT_RF_DATARATE (RF24_250KBPS) // Datarate
|
||||
|
||||
#include "NRF24_sniff_types.h"
|
||||
|
||||
static HM_Packets hmPackets;
|
||||
static uint32_t tickMillis;
|
||||
|
||||
|
||||
// Set up nRF24L01 radio on SPI bus plus CE/CS pins
|
||||
// If more than one RF24 unit is used the another CS pin than 10 must be used
|
||||
// This pin is used hard coded in SPI library
|
||||
static RF24 radio1 (RF1_CE_PIN, RF1_CS_PIN);
|
||||
|
||||
static NRF24_packet_t bufferData[PACKET_BUFFER_SIZE];
|
||||
|
||||
static CircularBuffer<NRF24_packet_t> packetBuffer(bufferData, sizeof(bufferData) / sizeof(bufferData[0]));
|
||||
|
||||
static Serial_header_t SerialHdr;
|
||||
|
||||
#define CHECKCRC 1
|
||||
static uint16_t lastCRC;
|
||||
static uint16_t crc;
|
||||
|
||||
uint8_t channels[] = {/*3,*/ 23, 40, 61, 75}; //{1, 3, 6, 9, 11, 23, 40, 61, 75}
|
||||
uint8_t channelIdx = 1; // fange mit 40 an
|
||||
uint8_t DEFAULT_SEND_CHANNEL = channels[channelIdx]; // = 40
|
||||
|
||||
static unsigned long timeLastPacket = millis();
|
||||
|
||||
// Function forward declaration
|
||||
static void SendPacket(uint64_t dest, uint8_t *buf, uint8_t len);
|
||||
char * getChannelName (uint8_t i);
|
||||
|
||||
static const int ANZAHL_VALUES = 16;
|
||||
static float VALUES[ANZAHL_VALUES] = {};
|
||||
static const char *CHANNEL_NAMES[ANZAHL_VALUES]
|
||||
= {"P1.Udc", "P1.Idc", "P1.Pdc", "P2.Udc", "P2.Idc", "P2.Pdc",
|
||||
"E-Woche", "E-Total", "E1-Tag", "E2-Tag", "Uac", "Freq.ac", "Pac", "E-heute", "Ipv", "WR-Temp"};
|
||||
static const uint8_t DIVISOR[ANZAHL_VALUES] = {10,100,10,10,100,10,1,1,1,1,10,100,10,0,0,10};
|
||||
|
||||
static const char BLANK = ' ';
|
||||
|
||||
static boolean istTag = true;
|
||||
|
||||
char CHANNELNAME_BUFFER[15];
|
||||
|
||||
#ifdef ESP8266
|
||||
#include "wifi.h"
|
||||
#include "ModWebserver.h"
|
||||
#include "Sonne.h"
|
||||
#endif
|
||||
|
||||
char * getChannelName (uint8_t i) {
|
||||
//-------------------------------
|
||||
memset (CHANNELNAME_BUFFER, 0, sizeof(CHANNELNAME_BUFFER));
|
||||
strcpy (CHANNELNAME_BUFFER, CHANNEL_NAMES[i]);
|
||||
//itoa (i, CHANNELNAME_BUFFER, 10);
|
||||
return CHANNELNAME_BUFFER;
|
||||
}
|
||||
|
||||
inline static void dumpData(uint8_t *p, int len) {
|
||||
//-----------------------------------------------
|
||||
while (len--){
|
||||
if (*p < 16)
|
||||
DEBUG_OUT.print(F("0"));
|
||||
DEBUG_OUT.print(*p++, HEX);
|
||||
}
|
||||
DEBUG_OUT.print(BLANK);
|
||||
}
|
||||
|
||||
|
||||
float extractValue2 (uint8_t *p, int divisor) {
|
||||
//-------------------------------------------
|
||||
uint16_t b1 = *p++;
|
||||
return ((float) (b1 << 8) + *p) / (float) divisor;
|
||||
}
|
||||
|
||||
|
||||
float extractValue4 (uint8_t *p, int divisor) {
|
||||
//-------------------------------------------
|
||||
uint32_t ret = *p++;
|
||||
for (uint8_t i = 1; i <= 3; i++)
|
||||
ret = (ret << 8) + *p++;
|
||||
return (ret / divisor);
|
||||
}
|
||||
|
||||
void outChannel (uint8_t i) {
|
||||
//-------------------------
|
||||
DEBUG_OUT.print(getChannelName(i)); DEBUG_OUT.print(F("\t:")); DEBUG_OUT.print(VALUES[i]); DEBUG_OUT.println(BLANK);
|
||||
}
|
||||
|
||||
|
||||
void analyse01 (uint8_t *p) { // p zeigt auf 01 hinter 2. WR-Adr
|
||||
//----------------------------------
|
||||
//uint16_t val;
|
||||
//DEBUG_OUT.print (F("analyse 01: "));
|
||||
p += 3;
|
||||
// PV1.U PV1.I PV1.P PV2.U PV2.I PV2.P
|
||||
// [0.1V] [0.01A] [.1W] [0.1V] [0.01A] [.1W]
|
||||
for (int i = 0; i < 6; i++) {
|
||||
VALUES[i] = extractValue2 (p,DIVISOR[i]); p += 2;
|
||||
outChannel(i);
|
||||
}
|
||||
/*
|
||||
DEBUG_OUT.print(F("PV1.U:")); DEBUG_OUT.print(extractValue2(p,10));
|
||||
p += 2;
|
||||
DEBUG_OUT.print(F(" PV1.I:")); DEBUG_OUT.print(extractValue2(p,100));
|
||||
p += 2;
|
||||
DEBUG_OUT.print(F(" PV1.Pac:")); DEBUG_OUT.print(extractValue2(p,10));
|
||||
p += 2;
|
||||
DEBUG_OUT.print(F(" PV2.U:")); DEBUG_OUT.print(extractValue2(p,10));
|
||||
p += 2;
|
||||
DEBUG_OUT.print(F(" PV2.I:")); DEBUG_OUT.print(extractValue2(p,100));
|
||||
p += 2;
|
||||
DEBUG_OUT.print(F(" PV2.Pac:")); DEBUG_OUT.print(extractValue2(p,10));
|
||||
*/
|
||||
DEBUG_OUT.println();
|
||||
}
|
||||
|
||||
|
||||
void analyse02 (uint8_t *p) { // p zeigt auf 02 hinter 2. WR-Adr
|
||||
//----------------------------------
|
||||
//uint16_t val;
|
||||
//DEBUG_OUT.print (F("analyse 02: "));
|
||||
// +11 = Spannung, +13 = Frequenz, +15 = Leistung
|
||||
//p += 11;
|
||||
p++;
|
||||
for (int i = 6; i < 13; i++) {
|
||||
if (i == 7) {
|
||||
VALUES[i] = extractValue4 (p,DIVISOR[i]);
|
||||
p += 4;
|
||||
}
|
||||
else {
|
||||
VALUES[i] = extractValue2 (p,DIVISOR[i]);
|
||||
p += 2;
|
||||
}
|
||||
outChannel(i);
|
||||
}
|
||||
VALUES[13] = VALUES[8] + VALUES[9]; // E-heute = P1+P2
|
||||
if (VALUES[10] > 0)
|
||||
VALUES[14] = VALUES[12] / VALUES[10]; // Ipv = Pac / Spannung
|
||||
/*
|
||||
DEBUG_OUT.print(F("P Woche:")); DEBUG_OUT.print(extractValue2(p,1));
|
||||
p += 2;
|
||||
DEBUG_OUT.print(F(" P Total:")); DEBUG_OUT.print(extractValue4(p,1));
|
||||
p += 4;
|
||||
DEBUG_OUT.print(F(" P1 Tag:")); DEBUG_OUT.print(extractValue2(p,1));
|
||||
p += 2;
|
||||
DEBUG_OUT.print(F(" P2 Tag:")); DEBUG_OUT.print(extractValue2(p,1));
|
||||
p += 2;
|
||||
|
||||
DEBUG_OUT.print(F(" Spannung:")); DEBUG_OUT.print(extractValue2(p,10));
|
||||
p += 2;
|
||||
DEBUG_OUT.print(F(" Freq.:")); DEBUG_OUT.print(extractValue2(p,100));
|
||||
p += 2;
|
||||
DEBUG_OUT.print(F(" Leist.:")); DEBUG_OUT.print(extractValue2(p,10));
|
||||
*/
|
||||
DEBUG_OUT.println();
|
||||
}
|
||||
|
||||
|
||||
void analyse83 (uint8_t *p) { // p zeigt auf 83 hinter 2. WR-Adr
|
||||
//----------------------------------
|
||||
//uint16_t val;
|
||||
//DEBUG_OUT.print (F("++++++analyse 83:"));
|
||||
p += 7;
|
||||
VALUES[15] = extractValue2 (p,DIVISOR[15]);
|
||||
outChannel(15);
|
||||
DEBUG_OUT.println();
|
||||
}
|
||||
|
||||
void analyseWords (uint8_t *p) { // p zeigt auf 01 hinter 2. WR-Adr
|
||||
//----------------------------------
|
||||
//uint16_t val;
|
||||
DEBUG_OUT.print (F("analyse words:"));
|
||||
p++;
|
||||
for (int i = 0; i <12;i++) {
|
||||
DEBUG_OUT.print(extractValue2(p,1));
|
||||
DEBUG_OUT.print(BLANK);
|
||||
p++;
|
||||
}
|
||||
DEBUG_OUT.println();
|
||||
}
|
||||
|
||||
void analyseLongs (uint8_t *p) { // p zeigt auf 01 hinter 2. WR-Adr
|
||||
//----------------------------------
|
||||
//uint16_t val;
|
||||
DEBUG_OUT.print (F("analyse words:"));
|
||||
p++;
|
||||
for (int i = 0; i <12;i++) {
|
||||
DEBUG_OUT.print(extractValue4(p,1));
|
||||
DEBUG_OUT.print(BLANK);
|
||||
p++;
|
||||
}
|
||||
DEBUG_OUT.println();
|
||||
}
|
||||
|
||||
|
||||
#ifdef ESP8266
|
||||
IRAM_ATTR
|
||||
#endif
|
||||
void handleNrf1Irq() {
|
||||
//-------------------------
|
||||
static uint8_t lostPacketCount = 0;
|
||||
uint8_t pipe;
|
||||
|
||||
DISABLE_EINT;
|
||||
|
||||
// Loop until RX buffer(s) contain no more packets.
|
||||
while (radio1.available(&pipe)) {
|
||||
if (!packetBuffer.full()) {
|
||||
NRF24_packet_t *p = packetBuffer.getFront();
|
||||
p->timestamp = micros(); // Micros does not increase in interrupt, but it can be used.
|
||||
p->packetsLost = lostPacketCount;
|
||||
uint8_t packetLen = radio1.getPayloadSize();
|
||||
if (packetLen > MAX_RF_PAYLOAD_SIZE)
|
||||
packetLen = MAX_RF_PAYLOAD_SIZE;
|
||||
|
||||
radio1.read(p->packet, packetLen);
|
||||
packetBuffer.pushFront(p);
|
||||
lostPacketCount = 0;
|
||||
}
|
||||
else {
|
||||
// Buffer full. Increase lost packet counter.
|
||||
bool tx_ok, tx_fail, rx_ready;
|
||||
if (lostPacketCount < 255)
|
||||
lostPacketCount++;
|
||||
// Call 'whatHappened' to reset interrupt status.
|
||||
radio1.whatHappened(tx_ok, tx_fail, rx_ready);
|
||||
// Flush buffer to drop the packet.
|
||||
radio1.flush_rx();
|
||||
}
|
||||
}
|
||||
ENABLE_EINT;
|
||||
}
|
||||
|
||||
|
||||
static void activateConf(void) {
|
||||
//-----------------------------
|
||||
radio1.setChannel(DEFAULT_RECV_CHANNEL);
|
||||
radio1.setDataRate(DEFAULT_RF_DATARATE);
|
||||
radio1.disableCRC();
|
||||
radio1.setAutoAck(0x00);
|
||||
radio1.setPayloadSize(MAX_RF_PAYLOAD_SIZE);
|
||||
radio1.setAddressWidth(5);
|
||||
radio1.openReadingPipe(1, DTU_RADIO_ID);
|
||||
|
||||
// We want only RX irqs
|
||||
radio1.maskIRQ(true, true, false);
|
||||
|
||||
// Use lo PA level, as a higher level will disturb CH340 DEBUG_OUT usb adapter
|
||||
radio1.setPALevel(RF24_PA_MAX);
|
||||
radio1.startListening();
|
||||
|
||||
// Attach interrupt handler to NRF IRQ output. Overwrites any earlier handler.
|
||||
attachInterrupt(digitalPinToInterrupt(RF1_IRQ_PIN), handleNrf1Irq, FALLING); // NRF24 Irq pin is active low.
|
||||
|
||||
// Initialize SerialHdr header's address member to promiscuous address.
|
||||
uint64_t addr = DTU_RADIO_ID;
|
||||
for (int8_t i = sizeof(SerialHdr.address) - 1; i >= 0; --i) {
|
||||
SerialHdr.address[i] = addr;
|
||||
addr >>= 8;
|
||||
}
|
||||
|
||||
#ifndef ESP8266
|
||||
DEBUG_OUT.println(F("\nRadio Config:"));
|
||||
radio1.printPrettyDetails();
|
||||
DEBUG_OUT.println();
|
||||
#endif
|
||||
tickMillis = millis() + 200;
|
||||
}
|
||||
|
||||
|
||||
void setup(void) {
|
||||
//--------------
|
||||
//Serial.begin(SER_BAUDRATE);
|
||||
DEBUG_OUT.begin(SER_BAUDRATE);
|
||||
DEBUG_OUT.flush();
|
||||
|
||||
DEBUG_OUT.println(F("-- Hoymiles DTU Simulation --"));
|
||||
|
||||
radio1.begin();
|
||||
|
||||
// Disable shockburst for receiving and decode payload manually
|
||||
radio1.setAutoAck(false);
|
||||
radio1.setRetries(0, 0);
|
||||
|
||||
// Configure nRF IRQ input
|
||||
pinMode(RF1_IRQ_PIN, INPUT);
|
||||
|
||||
activateConf();
|
||||
|
||||
#ifdef ESP8266
|
||||
setupWifi();
|
||||
setupClock();
|
||||
setupWebServer();
|
||||
setupUpdateByOTA();
|
||||
calcSunUpDown (getNow());
|
||||
istTag = isDayTime();
|
||||
DEBUG_OUT.print ("Es ist "); DEBUG_OUT.println (istTag?"Tag":"Nacht");
|
||||
hmPackets.SetUnixTimeStamp (getNow());
|
||||
#else
|
||||
hmPackets.SetUnixTimeStamp(0x62456430);
|
||||
#endif
|
||||
}
|
||||
|
||||
uint8_t sendBuf[MAX_RF_PAYLOAD_SIZE];
|
||||
|
||||
void isTime2Send () {
|
||||
//-----------------
|
||||
// Second timer
|
||||
|
||||
if (millis() >= tickMillis) {
|
||||
static uint8_t tel = 0;
|
||||
tickMillis += 1000; //200;
|
||||
//tickSec++;
|
||||
hmPackets.UnixTimeStampTick();
|
||||
/* if (++tickSec >= 5) { // 5
|
||||
hmPackets.UnixTimeStampTick();
|
||||
tickSec = 0;
|
||||
} */
|
||||
|
||||
int32_t size = 0;
|
||||
uint64_t dest = WR1_RADIO_ID;
|
||||
|
||||
if (tel > 5)
|
||||
tel = 0;
|
||||
|
||||
if (tel == 0) {
|
||||
#ifdef ESP8266
|
||||
hmPackets.SetUnixTimeStamp (getNow());
|
||||
#endif
|
||||
size = hmPackets.GetTimePacket((uint8_t *)&sendBuf, dest >> 8, DTU_RADIO_ID >> 8);
|
||||
}
|
||||
else if (tel == 1)
|
||||
size = hmPackets.GetCmdPacket((uint8_t *)&sendBuf, dest >> 8, DTU_RADIO_ID >> 8, 0x15, 0x81);
|
||||
else if (tel == 2)
|
||||
size = hmPackets.GetCmdPacket((uint8_t *)&sendBuf, dest >> 8, DTU_RADIO_ID >> 8, 0x15, 0x80);
|
||||
else if (tel == 3) {
|
||||
size = hmPackets.GetCmdPacket((uint8_t *)&sendBuf, dest >> 8, DTU_RADIO_ID >> 8, 0x15, 0x83);
|
||||
//tel = 0;
|
||||
}
|
||||
else if (tel == 4)
|
||||
size = hmPackets.GetCmdPacket((uint8_t *)&sendBuf, dest >> 8, DTU_RADIO_ID >> 8, 0x15, 0x82);
|
||||
else if (tel == 5)
|
||||
size = hmPackets.GetCmdPacket((uint8_t *)&sendBuf, dest >> 8, DTU_RADIO_ID >> 8, 0x15, 0x84);
|
||||
|
||||
SendPacket(dest, (uint8_t *)&sendBuf, size);
|
||||
|
||||
tel++;
|
||||
|
||||
/* for (uint8_t warte = 0; warte < 2; warte++) {
|
||||
delay(1000);
|
||||
hmPackets.UnixTimeStampTick();
|
||||
}*/
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void outputPacket(NRF24_packet_t *p, uint8_t payloadLen) {
|
||||
//-----------------------------------------------------
|
||||
|
||||
// Write timestamp, packets lost, address and payload length
|
||||
//printf(" %09lu ", SerialHdr.timestamp);
|
||||
dumpData((uint8_t *)&SerialHdr.packetsLost, sizeof(SerialHdr.packetsLost));
|
||||
dumpData((uint8_t *)&SerialHdr.address, sizeof(SerialHdr.address));
|
||||
|
||||
// Trailing bit?!?
|
||||
dumpData(&p->packet[0], 2);
|
||||
|
||||
// Payload length from PCF
|
||||
dumpData(&payloadLen, sizeof(payloadLen));
|
||||
|
||||
// Packet control field - PID Packet identification
|
||||
uint8_t val = (p->packet[1] >> 1) & 0x03;
|
||||
DEBUG_OUT.print(val);
|
||||
DEBUG_OUT.print(F(" "));
|
||||
|
||||
if (payloadLen > 9) {
|
||||
dumpData(&p->packet[2], 1);
|
||||
dumpData(&p->packet[3], 4);
|
||||
dumpData(&p->packet[7], 4);
|
||||
|
||||
uint16_t remain = payloadLen - 2 - 1 - 4 - 4 + 4;
|
||||
|
||||
if (remain < 32) {
|
||||
dumpData(&p->packet[11], remain);
|
||||
printf_P(PSTR("%04X "), crc);
|
||||
|
||||
if (((crc >> 8) != p->packet[payloadLen + 2]) || ((crc & 0xFF) != p->packet[payloadLen + 3]))
|
||||
DEBUG_OUT.print(0);
|
||||
else
|
||||
DEBUG_OUT.print(1);
|
||||
}
|
||||
else {
|
||||
DEBUG_OUT.print(F("Ill remain "));
|
||||
DEBUG_OUT.print(remain);
|
||||
}
|
||||
}
|
||||
else {
|
||||
dumpData(&p->packet[2], payloadLen + 2);
|
||||
printf_P(PSTR("%04X "), crc);
|
||||
}
|
||||
DEBUG_OUT.println();
|
||||
}
|
||||
|
||||
|
||||
void loop(void) {
|
||||
//=============
|
||||
while (!packetBuffer.empty()) {
|
||||
timeLastPacket = millis();
|
||||
// One or more records present
|
||||
NRF24_packet_t *p = packetBuffer.getBack();
|
||||
|
||||
// Shift payload data due to 9-bit packet control field
|
||||
for (int16_t j = sizeof(p->packet) - 1; j >= 0; j--) {
|
||||
if (j > 0)
|
||||
p->packet[j] = (byte)(p->packet[j] >> 7) | (byte)(p->packet[j - 1] << 1);
|
||||
else
|
||||
p->packet[j] = (byte)(p->packet[j] >> 7);
|
||||
}
|
||||
|
||||
SerialHdr.timestamp = p->timestamp;
|
||||
SerialHdr.packetsLost = p->packetsLost;
|
||||
|
||||
// Check CRC
|
||||
crc = 0xFFFF;
|
||||
crc = crc16((uint8_t *)&SerialHdr.address, sizeof(SerialHdr.address), crc, 0, BYTES_TO_BITS(sizeof(SerialHdr.address)));
|
||||
// Payload length
|
||||
uint8_t payloadLen = ((p->packet[0] & 0x01) << 5) | (p->packet[1] >> 3);
|
||||
// Add one byte and one bit for 9-bit packet control field
|
||||
crc = crc16((uint8_t *)&p->packet[0], sizeof(p->packet), crc, 7, BYTES_TO_BITS(payloadLen + 1) + 1);
|
||||
|
||||
if (CHECKCRC) {
|
||||
// If CRC is invalid only show lost packets
|
||||
if (((crc >> 8) != p->packet[payloadLen + 2]) || ((crc & 0xFF) != p->packet[payloadLen + 3])) {
|
||||
if (p->packetsLost > 0) {
|
||||
DEBUG_OUT.print(F(" Lost: "));
|
||||
DEBUG_OUT.println(p->packetsLost);
|
||||
}
|
||||
packetBuffer.popBack();
|
||||
continue;
|
||||
}
|
||||
|
||||
// Dump a decoded packet only once
|
||||
if (lastCRC == crc) {
|
||||
packetBuffer.popBack();
|
||||
continue;
|
||||
}
|
||||
lastCRC = crc;
|
||||
}
|
||||
|
||||
// Don't dump mysterious ack packages
|
||||
if (payloadLen == 0) {
|
||||
packetBuffer.popBack();
|
||||
continue;
|
||||
}
|
||||
|
||||
#ifdef DEBUG
|
||||
outputPacket (p, payloadLen);
|
||||
#endif
|
||||
|
||||
uint8_t cmd = p->packet[11];
|
||||
if (cmd == 0x02)
|
||||
analyse02 (&p->packet[11]);
|
||||
else if (cmd == 0x01)
|
||||
analyse01 (&p->packet[11]);
|
||||
//if (p->packet[11] == 0x83 || p->packet[11] == 0x82) analyse83 (&p->packet[11], payloadLen);
|
||||
else if (cmd == 0x03) {
|
||||
analyseWords (&p->packet[11]);
|
||||
analyseLongs (&p->packet[11]);
|
||||
}
|
||||
else if (cmd == 0x81) // ???
|
||||
;
|
||||
else if (cmd == 0x83)
|
||||
analyse83 (&p->packet[11]);
|
||||
else {
|
||||
DEBUG_OUT.print (F("---- neues cmd=")); DEBUG_OUT.println(cmd, HEX);
|
||||
analyseWords (&p->packet[11]);
|
||||
analyseLongs (&p->packet[11]);
|
||||
}
|
||||
if (p->packetsLost > 0) {
|
||||
DEBUG_OUT.print(F(" Lost: "));
|
||||
DEBUG_OUT.print(p->packetsLost);
|
||||
}
|
||||
DEBUG_OUT.println();
|
||||
|
||||
#ifndef ESP8266
|
||||
for (uint8_t i = 0; i < ANZAHL_VALUES; i++) {
|
||||
//outChannel(i);
|
||||
Serial.print(getChannelName(i)); Serial.print(':'); Serial.print(VALUES[i]); Serial.println(BLANK); // Schnittstelle bei Arduino
|
||||
}
|
||||
DEBUG_OUT.println();
|
||||
#endif
|
||||
|
||||
// Remove record as we're done with it.
|
||||
packetBuffer.popBack();
|
||||
}
|
||||
|
||||
if (istTag)
|
||||
isTime2Send();
|
||||
|
||||
#ifdef ESP8266
|
||||
checkWifi();
|
||||
webserverHandle();
|
||||
checkUpdateByOTA();
|
||||
if (hour() == 0 && minute() == 0) {
|
||||
calcSunUpDown(getNow());
|
||||
}
|
||||
if (minute() % 15 == 0 && second () == 0) { // alle 15 Minuten neu berechnen ob noch hell
|
||||
istTag = isDayTime();
|
||||
DEBUG_OUT.print ("Es ist "); DEBUG_OUT.println (istTag?"Tag":"Nacht");
|
||||
}
|
||||
#endif
|
||||
/*
|
||||
if (millis() > timeLastPacket + 60UL*SECOND) { // 60 Sekunden
|
||||
channelIdx++;
|
||||
if (channelIdx >= sizeof(channels)) channelIdx = 0;
|
||||
DEFAULT_SEND_CHANNEL = channels[channelIdx];
|
||||
DEBUG_OUT.print (F("\nneuer DEFAULT_SEND_CHANNEL: ")); DEBUG_OUT.println(DEFAULT_SEND_CHANNEL);
|
||||
timeLastPacket = millis();
|
||||
}
|
||||
*/
|
||||
}
|
||||
|
||||
|
||||
static void SendPacket(uint64_t dest, uint8_t *buf, uint8_t len) {
|
||||
//--------------------------------------------------------------
|
||||
DISABLE_EINT;
|
||||
radio1.stopListening();
|
||||
|
||||
#ifdef CHANNEL_HOP
|
||||
static uint8_t hop = 0;
|
||||
#if DEBUG_SEND
|
||||
DEBUG_OUT.print(F("Send... CH"));
|
||||
DEBUG_OUT.println(channels[hop]);
|
||||
#endif
|
||||
radio1.setChannel(channels[hop++]);
|
||||
if (hop >= sizeof(channels) / sizeof(channels[0]))
|
||||
hop = 0;
|
||||
#else
|
||||
radio1.setChannel(DEFAULT_SEND_CHANNEL);
|
||||
#endif
|
||||
|
||||
radio1.openWritingPipe(dest);
|
||||
radio1.setCRCLength(RF24_CRC_16);
|
||||
radio1.enableDynamicPayloads();
|
||||
radio1.setAutoAck(true);
|
||||
radio1.setRetries(3, 15);
|
||||
|
||||
radio1.write(buf, len);
|
||||
|
||||
// Try to avoid zero payload acks (has no effect)
|
||||
radio1.openWritingPipe(DUMMY_RADIO_ID);
|
||||
|
||||
radio1.setAutoAck(false);
|
||||
radio1.setRetries(0, 0);
|
||||
radio1.disableDynamicPayloads();
|
||||
radio1.setCRCLength(RF24_CRC_DISABLED);
|
||||
|
||||
radio1.setChannel(DEFAULT_RECV_CHANNEL);
|
||||
radio1.startListening();
|
||||
ENABLE_EINT;
|
||||
}
|
55
tools/NRF24_SendRcv/NRF24_sniff_types.h
Normal file
55
tools/NRF24_SendRcv/NRF24_sniff_types.h
Normal file
|
@ -0,0 +1,55 @@
|
|||
/*
|
||||
This file is part of NRF24_Sniff.
|
||||
|
||||
Created by Ivo Pullens, Emmission, 2014 -- www.emmission.nl
|
||||
|
||||
NRF24_Sniff is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
NRF24_Sniff is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with NRF24_Sniff. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifndef NRF24_sniff_types_h
|
||||
#define NRF24_sniff_types_h
|
||||
|
||||
typedef struct _NRF24_packet_t
|
||||
{
|
||||
uint32_t timestamp;
|
||||
uint8_t packetsLost;
|
||||
uint8_t packet[MAX_RF_PAYLOAD_SIZE];
|
||||
} NRF24_packet_t;
|
||||
|
||||
typedef struct _Serial_header_t
|
||||
{
|
||||
unsigned long timestamp;
|
||||
uint8_t packetsLost;
|
||||
uint8_t address[RF_MAX_ADDR_WIDTH]; // MSB first, always RF_MAX_ADDR_WIDTH bytes.
|
||||
} Serial_header_t;
|
||||
|
||||
typedef struct _Serial_config_t
|
||||
{
|
||||
uint8_t channel;
|
||||
uint8_t rate; // rf24_datarate_e: 0 = 1Mb/s, 1 = 2Mb/s, 2 = 250Kb/s
|
||||
uint8_t addressLen; // Number of bytes used in address, range [2..5]
|
||||
uint8_t addressPromiscLen; // Number of bytes used in promiscuous address, range [2..5]. E.g. addressLen=5, addressPromiscLen=4 => 1 byte unique identifier.
|
||||
uint64_t address; // Base address, LSB first.
|
||||
uint8_t crcLength; // Length of active CRC, range [0..2]
|
||||
uint8_t maxPayloadSize; // Maximum size of payload for nRF (including nRF header), range[4?..32]
|
||||
} Serial_config_t;
|
||||
|
||||
#define MSG_TYPE_PACKET (0)
|
||||
#define MSG_TYPE_CONFIG (1)
|
||||
|
||||
#define SET_MSG_TYPE(var,type) (((var) & 0x3F) | ((type) << 6))
|
||||
#define GET_MSG_TYPE(var) ((var) >> 6)
|
||||
#define GET_MSG_LEN(var) ((var) & 0x3F)
|
||||
|
||||
#endif // NRF24_sniff_types_h
|
82
tools/NRF24_SendRcv/Settings.h
Normal file
82
tools/NRF24_SendRcv/Settings.h
Normal file
|
@ -0,0 +1,82 @@
|
|||
#ifndef __SETTINGS_H
|
||||
#define __SETTINGS_H
|
||||
|
||||
// Ausgabe von Debug Infos auf der seriellen Console
|
||||
#define DEBUG
|
||||
#define SER_BAUDRATE (115200)
|
||||
|
||||
// Ausgabe was gesendet wird; 0 oder 1
|
||||
#define DEBUG_SEND 0
|
||||
|
||||
// soll zwichen den Sendekanälen 23, 40, 61, 75 ständig gewechselt werden
|
||||
#define CHANNEL_HOP
|
||||
|
||||
// mit OTA Support, also update der Firmware über WLan mittels IP/update
|
||||
#define WITH_OTA
|
||||
|
||||
// Hardware configuration
|
||||
#ifdef ESP8266
|
||||
#define RF1_CE_PIN (D4)
|
||||
#define RF1_CS_PIN (D8)
|
||||
#define RF1_IRQ_PIN (D3)
|
||||
#else
|
||||
#define RF1_CE_PIN (9)
|
||||
#define RF1_CS_PIN (10)
|
||||
#define RF1_IRQ_PIN (2)
|
||||
#endif
|
||||
|
||||
union longlongasbytes {
|
||||
uint64_t ull;
|
||||
uint8_t bytes[8];
|
||||
};
|
||||
|
||||
|
||||
uint64_t Serial2RadioID (uint64_t sn) {
|
||||
//----------------------------------
|
||||
longlongasbytes llsn;
|
||||
longlongasbytes res;
|
||||
llsn.ull = sn;
|
||||
res.ull = 0;
|
||||
res.bytes[4] = llsn.bytes[0];
|
||||
res.bytes[3] = llsn.bytes[1];
|
||||
res.bytes[2] = llsn.bytes[2];
|
||||
res.bytes[1] = llsn.bytes[3];
|
||||
res.bytes[0] = 0x01;
|
||||
return res.ull;
|
||||
}
|
||||
|
||||
// WR und DTU
|
||||
#define DUMMY_RADIO_ID ((uint64_t)0xDEADBEEF01ULL)
|
||||
#define SerialWR 0x114172607952ULL // <<<<<<<<<<<<<<<<<<<<<<< anpassen
|
||||
uint64_t WR1_RADIO_ID = Serial2RadioID (SerialWR); // ((uint64_t)0x5279607201ULL);
|
||||
#define DTU_RADIO_ID ((uint64_t)0x1234567801ULL)
|
||||
|
||||
|
||||
// Webserver
|
||||
#define WEBSERVER_PORT 80
|
||||
|
||||
// Time Server
|
||||
//#define TIMESERVER_NAME "pool.ntp.org"
|
||||
#define TIMESERVER_NAME "fritz.box"
|
||||
|
||||
#ifdef WITH_OTA
|
||||
// OTA Einstellungen
|
||||
#define UPDATESERVER_PORT WEBSERVER_PORT+1
|
||||
#define UPDATESERVER_DIR "/update" // mittels IP:81/update kommt man dann auf die OTA-Seite
|
||||
#define UPDATESERVER_USER "username_für_OTA" // <<<<<<<<<<<<<<<<<<<<<<< anpassen
|
||||
#define UPDATESERVER_PW "passwort_für_OTA" // <<<<<<<<<<<<<<<<<<<<<<< anpassen
|
||||
#endif
|
||||
|
||||
// internes WLan
|
||||
// PREFIXE dienen dazu, die eigenen WLans (wenn mehrere) vonfremden zu unterscheiden
|
||||
// gehe hier davon aus, dass alle WLans das gleiche Passwort haben. Wenn nicht, dann mehre Passwörter hinterlegen
|
||||
#define SSID_PREFIX1 "wlan1-Prefix" // <<<<<<<<<<<<<<<<<<<<<<< anpassen
|
||||
#define SSID_PREFIX2 "wlan2-Prefix" // <<<<<<<<<<<<<<<<<<<<<<< anpassen
|
||||
#define SSID_PASSWORD "wlan-passwort" // <<<<<<<<<<<<<<<<<<<<<<< anpassen
|
||||
|
||||
// zur Berechnung von Sonnenauf- und -untergang
|
||||
#define geoBreite 49.2866
|
||||
#define geoLaenge 7.3416
|
||||
|
||||
|
||||
#endif
|
55
tools/NRF24_SendRcv/Sonne.h
Normal file
55
tools/NRF24_SendRcv/Sonne.h
Normal file
|
@ -0,0 +1,55 @@
|
|||
#ifndef __SONNE_H
|
||||
#define __SONNE_H
|
||||
|
||||
#include "Settings.h"
|
||||
#include "Debug.h"
|
||||
|
||||
|
||||
long SunDown, SunUp;
|
||||
|
||||
void calcSunUpDown (time_t date) {
|
||||
//SunUpDown res = new SunUpDown();
|
||||
boolean isSummerTime = false; // TODO TimeZone.getDefault().inDaylightTime(new Date(date));
|
||||
|
||||
//- Bogenma<6D>
|
||||
double brad = geoBreite / 180.0 * PI;
|
||||
// - H<>he Sonne -50 Bogenmin.
|
||||
double h0 = -50.0 / 60.0 / 180.0 * PI;
|
||||
//- Deklination dek, Tag des Jahres d0
|
||||
int tage = 30 * month(date) - 30 + day(date);
|
||||
double dek = 0.40954 * sin (0.0172 * (tage - 79.35));
|
||||
double zh1 = sin (h0) - sin (brad) * sin(dek);
|
||||
double zh2 = cos(brad) * cos(dek);
|
||||
double zd = 12*acos (zh1/zh2) / PI;
|
||||
double zgl = -0.1752 * sin (0.03343 * tage + 0.5474) - 0.134 * sin (0.018234 * tage - 0.1939);
|
||||
//-Sonnenuntergang
|
||||
double tsu = 12 + zd - zgl;
|
||||
double su = (tsu + (15.0 - geoLaenge) / 15.0);
|
||||
int std = (int)su;
|
||||
int minute = (int) ((su - std)*60);
|
||||
if (isSummerTime) std++;
|
||||
SunDown = (100*std + minute) * 100;
|
||||
|
||||
//- Sonnenaufgang
|
||||
double tsa = 12 - zd - zgl;
|
||||
double sa = (tsa + (15.0 - geoLaenge) /15.0);
|
||||
std = (int) sa;
|
||||
minute = (int) ((sa - std)*60);
|
||||
if (isSummerTime) std++;
|
||||
SunUp = (100*std + minute) * 100;
|
||||
DEBUG_OUT.print("Sonnenaufgang :"); DEBUG_OUT.println(SunUp);
|
||||
DEBUG_OUT.print("Sonnenuntergang:"); DEBUG_OUT.println(SunDown);
|
||||
}
|
||||
|
||||
boolean isDayTime() {
|
||||
//-----------------
|
||||
// 900 = 15 Minuten, vor Sonnenaufgang und nach -untergang
|
||||
const int offset=60*15;
|
||||
time_t no = getNow();
|
||||
long jetztMinuteU = (100 * hour(no+offset) + minute(no+offset)) * 100;
|
||||
long jetztMinuteO = (100 * hour(no-offset) + minute(no-offset)) * 100;
|
||||
|
||||
return ((jetztMinuteU >= SunUp) &&(jetztMinuteO <= SunDown));
|
||||
}
|
||||
|
||||
#endif
|
142
tools/NRF24_SendRcv/hm_crc.cpp
Normal file
142
tools/NRF24_SendRcv/hm_crc.cpp
Normal file
|
@ -0,0 +1,142 @@
|
|||
|
||||
#include <stdio.h>
|
||||
#include <stdint.h>
|
||||
#include "hm_crc.h"
|
||||
//#define OUTPUT_DEBUG_INFO
|
||||
|
||||
/* Table of CRC values for high-order byte */
|
||||
static const uint8_t auchCRCHi[] = {
|
||||
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81,
|
||||
0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0,
|
||||
0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01,
|
||||
0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41,
|
||||
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81,
|
||||
0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0,
|
||||
0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01,
|
||||
0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40,
|
||||
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81,
|
||||
0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0,
|
||||
0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01,
|
||||
0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
|
||||
0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81,
|
||||
0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0,
|
||||
0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01,
|
||||
0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41,
|
||||
0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81,
|
||||
0x40};
|
||||
|
||||
/* Table of CRC values for low-order byte */
|
||||
static const uint8_t auchCRCLo[] = {
|
||||
0x00, 0xC0, 0xC1, 0x01, 0xC3, 0x03, 0x02, 0xC2, 0xC6, 0x06, 0x07, 0xC7, 0x05, 0xC5, 0xC4,
|
||||
0x04, 0xCC, 0x0C, 0x0D, 0xCD, 0x0F, 0xCF, 0xCE, 0x0E, 0x0A, 0xCA, 0xCB, 0x0B, 0xC9, 0x09,
|
||||
0x08, 0xC8, 0xD8, 0x18, 0x19, 0xD9, 0x1B, 0xDB, 0xDA, 0x1A, 0x1E, 0xDE, 0xDF, 0x1F, 0xDD,
|
||||
0x1D, 0x1C, 0xDC, 0x14, 0xD4, 0xD5, 0x15, 0xD7, 0x17, 0x16, 0xD6, 0xD2, 0x12, 0x13, 0xD3,
|
||||
0x11, 0xD1, 0xD0, 0x10, 0xF0, 0x30, 0x31, 0xF1, 0x33, 0xF3, 0xF2, 0x32, 0x36, 0xF6, 0xF7,
|
||||
0x37, 0xF5, 0x35, 0x34, 0xF4, 0x3C, 0xFC, 0xFD, 0x3D, 0xFF, 0x3F, 0x3E, 0xFE, 0xFA, 0x3A,
|
||||
0x3B, 0xFB, 0x39, 0xF9, 0xF8, 0x38, 0x28, 0xE8, 0xE9, 0x29, 0xEB, 0x2B, 0x2A, 0xEA, 0xEE,
|
||||
0x2E, 0x2F, 0xEF, 0x2D, 0xED, 0xEC, 0x2C, 0xE4, 0x24, 0x25, 0xE5, 0x27, 0xE7, 0xE6, 0x26,
|
||||
0x22, 0xE2, 0xE3, 0x23, 0xE1, 0x21, 0x20, 0xE0, 0xA0, 0x60, 0x61, 0xA1, 0x63, 0xA3, 0xA2,
|
||||
0x62, 0x66, 0xA6, 0xA7, 0x67, 0xA5, 0x65, 0x64, 0xA4, 0x6C, 0xAC, 0xAD, 0x6D, 0xAF, 0x6F,
|
||||
0x6E, 0xAE, 0xAA, 0x6A, 0x6B, 0xAB, 0x69, 0xA9, 0xA8, 0x68, 0x78, 0xB8, 0xB9, 0x79, 0xBB,
|
||||
0x7B, 0x7A, 0xBA, 0xBE, 0x7E, 0x7F, 0xBF, 0x7D, 0xBD, 0xBC, 0x7C, 0xB4, 0x74, 0x75, 0xB5,
|
||||
0x77, 0xB7, 0xB6, 0x76, 0x72, 0xB2, 0xB3, 0x73, 0xB1, 0x71, 0x70, 0xB0, 0x50, 0x90, 0x91,
|
||||
0x51, 0x93, 0x53, 0x52, 0x92, 0x96, 0x56, 0x57, 0x97, 0x55, 0x95, 0x94, 0x54, 0x9C, 0x5C,
|
||||
0x5D, 0x9D, 0x5F, 0x9F, 0x9E, 0x5E, 0x5A, 0x9A, 0x9B, 0x5B, 0x99, 0x59, 0x58, 0x98, 0x88,
|
||||
0x48, 0x49, 0x89, 0x4B, 0x8B, 0x8A, 0x4A, 0x4E, 0x8E, 0x8F, 0x4F, 0x8D, 0x4D, 0x4C, 0x8C,
|
||||
0x44, 0x84, 0x85, 0x45, 0x87, 0x47, 0x46, 0x86, 0x82, 0x42, 0x43, 0x83, 0x41, 0x81, 0x80,
|
||||
0x40};
|
||||
|
||||
uint16_t crc16_modbus(uint8_t *puchMsg, uint16_t usDataLen)
|
||||
{
|
||||
uint8_t uchCRCHi = 0xFF; /* high byte of CRC initialized */
|
||||
uint8_t uchCRCLo = 0xFF; /* low byte of CRC initialized */
|
||||
uint16_t uIndex; /* will index into CRC lookup table */
|
||||
while (usDataLen--) /* pass through message buffer */
|
||||
{
|
||||
uIndex = uchCRCLo ^ *puchMsg++; /* calculate the CRC */
|
||||
uchCRCLo = uchCRCHi ^ auchCRCHi[uIndex];
|
||||
uchCRCHi = auchCRCLo[uIndex];
|
||||
}
|
||||
return (uchCRCHi << 8 | uchCRCLo);
|
||||
}
|
||||
|
||||
// Hoymiles CRC8 calculation with poly 0x01, Initial value 0x00 and final XOR 0x00
|
||||
uint8_t crc8(uint8_t *buf, const uint16_t bufLen)
|
||||
{
|
||||
uint32_t crc;
|
||||
uint16_t i, bit;
|
||||
|
||||
crc = 0x00;
|
||||
for (i = 0; i < bufLen; i++)
|
||||
{
|
||||
crc ^= buf[i];
|
||||
for (bit = 0; bit < 8; bit++)
|
||||
{
|
||||
if ((crc & 0x80) != 0)
|
||||
{
|
||||
crc <<= 1;
|
||||
crc ^= 0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
crc <<= 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return (crc & 0xFF);
|
||||
}
|
||||
|
||||
// NRF24 CRC16 calculation with poly 0x1021 = (1) 0001 0000 0010 0001 = x^16+x^12+x^5+1
|
||||
uint16_t crc16(uint8_t *buf, const uint16_t bufLen, const uint16_t startCRC, const uint16_t startBit, const uint16_t len_bits)
|
||||
{
|
||||
uint16_t crc = startCRC;
|
||||
if ((len_bits > 0) && (len_bits <= BYTES_TO_BITS(bufLen)))
|
||||
{
|
||||
// The length of the data might not be a multiple of full bytes.
|
||||
// Therefore we proceed over the data bit-by-bit (like the NRF24 does) to
|
||||
// calculate the CRC.
|
||||
uint16_t data;
|
||||
uint8_t byte, shift;
|
||||
uint16_t bitoffs = startBit;
|
||||
|
||||
// Get a new byte for the next 8 bits.
|
||||
byte = buf[bitoffs >> 3];
|
||||
#ifdef OUTPUT_DEBUG_INFO
|
||||
printf("\nStart CRC %04X, %u bits:", startCRC, len_bits);
|
||||
printf("\nbyte %02X:", byte);
|
||||
#endif
|
||||
while (bitoffs < len_bits + startBit)
|
||||
{
|
||||
shift = bitoffs & 7;
|
||||
// Shift the active bit to the position of bit 15
|
||||
data = ((uint16_t)byte) << (8 + shift);
|
||||
#ifdef OUTPUT_DEBUG_INFO
|
||||
printf(" bit %u %u,", shift, data & 0x8000 ? 1 : 0);
|
||||
#endif
|
||||
// Assure all other bits are 0
|
||||
data &= 0x8000;
|
||||
crc ^= data;
|
||||
if (crc & 0x8000)
|
||||
{
|
||||
crc = (crc << 1) ^ 0x1021; // 0x1021 = (1) 0001 0000 0010 0001 = x^16+x^12+x^5+1
|
||||
}
|
||||
else
|
||||
{
|
||||
crc = (crc << 1);
|
||||
}
|
||||
++bitoffs;
|
||||
if (0 == (bitoffs & 7))
|
||||
{
|
||||
// Get a new byte for the next 8 bits.
|
||||
byte = buf[bitoffs >> 3];
|
||||
#ifdef OUTPUT_DEBUG_INFO
|
||||
printf("crc %04X:", crc);
|
||||
if (bitoffs < len_bits + startBit)
|
||||
printf("\nbyte %02X:", byte);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
return crc;
|
||||
}
|
8
tools/NRF24_SendRcv/hm_crc.h
Normal file
8
tools/NRF24_SendRcv/hm_crc.h
Normal file
|
@ -0,0 +1,8 @@
|
|||
|
||||
|
||||
#define BITS_TO_BYTES(x) (((x)+7)>>3)
|
||||
#define BYTES_TO_BITS(x) ((x)<<3)
|
||||
|
||||
extern uint16_t crc16_modbus(uint8_t *puchMsg, uint16_t usDataLen);
|
||||
extern uint8_t crc8(uint8_t *buf, const uint16_t bufLen);
|
||||
extern uint16_t crc16(uint8_t* buf, const uint16_t bufLen, const uint16_t startCRC, const uint16_t startBit, const uint16_t len_bits);
|
74
tools/NRF24_SendRcv/hm_packets.cpp
Normal file
74
tools/NRF24_SendRcv/hm_packets.cpp
Normal file
|
@ -0,0 +1,74 @@
|
|||
#include "Arduino.h"
|
||||
|
||||
#include "hm_crc.h"
|
||||
#include "hm_packets.h"
|
||||
|
||||
void HM_Packets::SetUnixTimeStamp(uint32_t ts)
|
||||
{
|
||||
unixTimeStamp = ts;
|
||||
}
|
||||
|
||||
void HM_Packets::UnixTimeStampTick()
|
||||
{
|
||||
unixTimeStamp++;
|
||||
}
|
||||
|
||||
void HM_Packets::prepareBuffer(uint8_t *buf)
|
||||
{
|
||||
// minimal buffer size of 32 bytes is assumed
|
||||
memset(buf, 0x00, 32);
|
||||
}
|
||||
|
||||
void HM_Packets::copyToBuffer(uint8_t *buf, uint32_t val)
|
||||
{
|
||||
buf[0]= (uint8_t)(val >> 24);
|
||||
buf[1]= (uint8_t)(val >> 16);
|
||||
buf[2]= (uint8_t)(val >> 8);
|
||||
buf[3]= (uint8_t)(val & 0xFF);
|
||||
}
|
||||
|
||||
void HM_Packets::copyToBufferBE(uint8_t *buf, uint32_t val)
|
||||
{
|
||||
memcpy(buf, &val, sizeof(uint32_t));
|
||||
}
|
||||
|
||||
|
||||
int32_t HM_Packets::GetTimePacket(uint8_t *buf, uint32_t wrAdr, uint32_t dtuAdr)
|
||||
{
|
||||
prepareBuffer(buf);
|
||||
|
||||
buf[0] = 0x15;
|
||||
copyToBufferBE(&buf[1], wrAdr);
|
||||
copyToBufferBE(&buf[5], dtuAdr);
|
||||
buf[9] = 0x80;
|
||||
|
||||
buf[10] = 0x0B; // cid
|
||||
buf[11] = 0x00;
|
||||
|
||||
copyToBuffer(&buf[12], unixTimeStamp);
|
||||
|
||||
buf[19] = 0x05;
|
||||
|
||||
// CRC16
|
||||
uint16_t crc16 = crc16_modbus(&buf[10], 14);
|
||||
buf[24] = crc16 >> 8;
|
||||
buf[25] = crc16 & 0xFF;
|
||||
|
||||
// crc8
|
||||
buf[26] = crc8(&buf[0], 26);
|
||||
|
||||
return 27;
|
||||
}
|
||||
|
||||
int32_t HM_Packets::GetCmdPacket(uint8_t *buf, uint32_t wrAdr, uint32_t dtuAdr, uint8_t mid, uint8_t cmd)
|
||||
{
|
||||
buf[0] = mid;
|
||||
copyToBufferBE(&buf[1], wrAdr);
|
||||
copyToBufferBE(&buf[5], dtuAdr);
|
||||
buf[9] = cmd;
|
||||
|
||||
// crc8
|
||||
buf[10] = crc8(&buf[0], 10);
|
||||
|
||||
return 11;
|
||||
}
|
18
tools/NRF24_SendRcv/hm_packets.h
Normal file
18
tools/NRF24_SendRcv/hm_packets.h
Normal file
|
@ -0,0 +1,18 @@
|
|||
|
||||
|
||||
class HM_Packets
|
||||
{
|
||||
private:
|
||||
uint32_t unixTimeStamp;
|
||||
|
||||
void prepareBuffer(uint8_t *buf);
|
||||
void copyToBuffer(uint8_t *buf, uint32_t val);
|
||||
void copyToBufferBE(uint8_t *buf, uint32_t val);
|
||||
|
||||
public:
|
||||
void SetUnixTimeStamp(uint32_t ts);
|
||||
void UnixTimeStampTick();
|
||||
|
||||
int32_t GetTimePacket(uint8_t *buf, uint32_t wrAdr, uint32_t dtuAdr);
|
||||
int32_t GetCmdPacket(uint8_t *buf, uint32_t wrAdr, uint32_t dtuAdr, uint8_t mid, uint8_t cmd);
|
||||
};
|
345
tools/NRF24_SendRcv/wifi.h
Normal file
345
tools/NRF24_SendRcv/wifi.h
Normal file
|
@ -0,0 +1,345 @@
|
|||
#ifndef __WIFI_H
|
||||
#define __WIFI_H
|
||||
|
||||
#include "Settings.h"
|
||||
#include "Debug.h"
|
||||
#include <ESP8266WiFi.h>
|
||||
#include <Pinger.h> // von url=https://www.technologytourist.com
|
||||
|
||||
String SSID = ""; // bestes WLan
|
||||
|
||||
// Prototypes
|
||||
time_t getNow ();
|
||||
boolean setupWifi ();
|
||||
boolean checkWifi();
|
||||
|
||||
|
||||
String findWifi () {
|
||||
//----------------
|
||||
String ssid;
|
||||
int32_t rssi;
|
||||
uint8_t encryptionType;
|
||||
uint8_t* bssid;
|
||||
int32_t channel;
|
||||
bool hidden;
|
||||
int scanResult;
|
||||
|
||||
String best_ssid = "";
|
||||
int32_t best_rssi = -100;
|
||||
|
||||
DEBUG_OUT.println(F("Starting WiFi scan..."));
|
||||
|
||||
scanResult = WiFi.scanNetworks(/*async=*/false, /*hidden=*/true);
|
||||
|
||||
if (scanResult == 0) {
|
||||
DEBUG_OUT.println(F("keine WLans"));
|
||||
} else if (scanResult > 0) {
|
||||
DEBUG_OUT.printf(PSTR("%d WLans gefunden:\n"), scanResult);
|
||||
|
||||
// Print unsorted scan results
|
||||
for (int8_t i = 0; i < scanResult; i++) {
|
||||
WiFi.getNetworkInfo(i, ssid, encryptionType, rssi, bssid, channel, hidden);
|
||||
|
||||
DEBUG_OUT.printf(PSTR(" %02d: [CH %02d] [%02X:%02X:%02X:%02X:%02X:%02X] %ddBm %c %c %s\n"),
|
||||
i,
|
||||
channel,
|
||||
bssid[0], bssid[1], bssid[2],
|
||||
bssid[3], bssid[4], bssid[5],
|
||||
rssi,
|
||||
(encryptionType == ENC_TYPE_NONE) ? ' ' : '*',
|
||||
hidden ? 'H' : 'V',
|
||||
ssid.c_str());
|
||||
delay(1);
|
||||
boolean check;
|
||||
#ifdef SSID_PREFIX1
|
||||
check = ssid.substring(0,strlen(SSID_PREFIX1)).equals(SSID_PREFIX1);
|
||||
#else
|
||||
check = true;
|
||||
#endif
|
||||
#ifdef SSID_PREFIX2
|
||||
check = check || ssid.substring(0,strlen(SSID_PREFIX2)).equals(SSID_PREFIX2);
|
||||
#endif
|
||||
if (check) {
|
||||
if (rssi > best_rssi) {
|
||||
best_rssi = rssi;
|
||||
best_ssid = ssid;
|
||||
}
|
||||
}
|
||||
}
|
||||
} else {
|
||||
DEBUG_OUT.printf(PSTR("WiFi scan error %d"), scanResult);
|
||||
}
|
||||
|
||||
if (! best_ssid.equals("")) {
|
||||
SSID = best_ssid;
|
||||
DEBUG_OUT.printf ("Bestes Wifi unter: %s\n", SSID.c_str());
|
||||
return SSID;
|
||||
}
|
||||
else
|
||||
return "";
|
||||
}
|
||||
|
||||
void IP2string (IPAddress IP, char * buf) {
|
||||
sprintf (buf, "%d.%d.%d.%d", IP[0], IP[1], IP[2], IP[3]);
|
||||
}
|
||||
|
||||
void connectWifi() {
|
||||
//------------------
|
||||
// if (SSID.equals(""))
|
||||
String s = findWifi();
|
||||
|
||||
if (!SSID.equals("")) {
|
||||
DEBUG_OUT.print("versuche zu verbinden mit "); DEBUG_OUT.println(SSID);
|
||||
//while (WiFi.status() != WL_CONNECTED) {
|
||||
WiFi.begin (SSID, SSID_PASSWORD);
|
||||
int versuche = 20;
|
||||
while (WiFi.status() != WL_CONNECTED && versuche > 0) {
|
||||
delay(1000);
|
||||
versuche--;
|
||||
DEBUG_OUT.print(versuche); DEBUG_OUT.print(' ');
|
||||
}
|
||||
//}
|
||||
if (WiFi.status() == WL_CONNECTED) {
|
||||
char buffer[30];
|
||||
IP2string (WiFi.localIP(), buffer);
|
||||
String out = "\n[WiFi]Verbunden; meine IP:" + String (buffer);
|
||||
DEBUG_OUT.println (out);
|
||||
}
|
||||
else
|
||||
DEBUG_OUT.print("\nkeine Verbindung mit SSID "); DEBUG_OUT.println(SSID);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
boolean setupWifi () {
|
||||
//------------------
|
||||
int count=5;
|
||||
while (count-- && WiFi.status() != WL_CONNECTED)
|
||||
connectWifi();
|
||||
return (WiFi.status() == WL_CONNECTED);
|
||||
}
|
||||
|
||||
|
||||
Pinger pinger;
|
||||
IPAddress ROUTER = IPAddress(192,168,1,1);
|
||||
|
||||
boolean checkWifi() {
|
||||
//---------------
|
||||
boolean NotConnected = (WiFi.status() != WL_CONNECTED) || !pinger.Ping(ROUTER);
|
||||
if (NotConnected) {
|
||||
setupWifi();
|
||||
if (WiFi.status() == WL_CONNECTED)
|
||||
getNow();
|
||||
}
|
||||
return (WiFi.status() == WL_CONNECTED);
|
||||
}
|
||||
|
||||
|
||||
|
||||
// ################ Clock #################
|
||||
|
||||
#include <WiFiUdp.h>
|
||||
#include <TimeLib.h>
|
||||
|
||||
IPAddress timeServer;
|
||||
unsigned int localPort = 8888;
|
||||
const int NTP_PACKET_SIZE= 48; // NTP time stamp is in the first 48 bytes of the message
|
||||
byte packetBuf[NTP_PACKET_SIZE]; // Buffer to hold incoming and outgoing packets
|
||||
const int timeZone = 1; // Central European Time = +1
|
||||
long SYNCINTERVALL = 0;
|
||||
WiFiUDP Udp; // A UDP instance to let us send and receive packets over UDP
|
||||
|
||||
// prototypes
|
||||
time_t getNtpTime ();
|
||||
void sendNTPpacket (IPAddress &address);
|
||||
time_t getNow ();
|
||||
char* getDateTimeStr (time_t no = getNow());
|
||||
time_t offsetDayLightSaving (uint32_t local_t);
|
||||
bool isDayofDaylightChange (time_t local_t);
|
||||
|
||||
|
||||
void _setSyncInterval (long intervall) {
|
||||
//----------------------------------------
|
||||
SYNCINTERVALL = intervall;
|
||||
setSyncInterval (intervall);
|
||||
}
|
||||
|
||||
void setupClock() {
|
||||
//-----------------
|
||||
WiFi.hostByName (TIMESERVER_NAME,timeServer); // at this point the function works
|
||||
|
||||
Udp.begin(localPort);
|
||||
|
||||
getNtpTime();
|
||||
|
||||
setSyncProvider (getNtpTime);
|
||||
while(timeStatus()== timeNotSet)
|
||||
delay(1); //
|
||||
|
||||
_setSyncInterval (SECS_PER_DAY / 2); // Set seconds between re-sync
|
||||
|
||||
//lastClock = now();
|
||||
//Serial.print("[NTP] get time from NTP server ");
|
||||
getNow();
|
||||
//char buf[20];
|
||||
DEBUG_OUT.print ("[NTP] get time from NTP server ");
|
||||
DEBUG_OUT.print (timeServer);
|
||||
//sprintf (buf, ": %02d:%02d:%02d", hour(no), minute(no), second(no));
|
||||
DEBUG_OUT.print (": got ");
|
||||
DEBUG_OUT.println (getDateTimeStr());
|
||||
}
|
||||
|
||||
//*-------- NTP code ----------*/
|
||||
|
||||
|
||||
time_t getNtpTime() {
|
||||
//-------------------
|
||||
sendNTPpacket(timeServer); // send an NTP packet to a time server
|
||||
//uint32_t beginWait = millis();
|
||||
//while (millis() - beginWait < 1500) {
|
||||
int versuch = 0;
|
||||
while (versuch < 5) {
|
||||
int wait = 150; // results in max 1500 ms waitTime
|
||||
while (wait--) {
|
||||
int size = Udp.parsePacket();
|
||||
if (size >= NTP_PACKET_SIZE) {
|
||||
//Serial.println("Receive NTP Response");
|
||||
Udp.read(packetBuf, NTP_PACKET_SIZE); // read packet into the buffer
|
||||
unsigned long secsSince1900;
|
||||
// convert four bytes starting at location 40 to a long integer
|
||||
secsSince1900 = (unsigned long)packetBuf[40] << 24;
|
||||
secsSince1900 |= (unsigned long)packetBuf[41] << 16;
|
||||
secsSince1900 |= (unsigned long)packetBuf[42] << 8;
|
||||
secsSince1900 |= (unsigned long)packetBuf[43];
|
||||
// time_t now = secsSince1900 - 2208988800UL + timeZone * SECS_PER_HOUR;
|
||||
|
||||
time_t utc = secsSince1900 - 2208988800UL;
|
||||
time_t now = utc + (timeZone +offsetDayLightSaving(utc)) * SECS_PER_HOUR;
|
||||
|
||||
if (isDayofDaylightChange (utc) && hour(utc) <= 4)
|
||||
_setSyncInterval (SECS_PER_HOUR);
|
||||
else
|
||||
_setSyncInterval (SECS_PER_DAY / 2);
|
||||
|
||||
return now;
|
||||
}
|
||||
else
|
||||
delay(10);
|
||||
}
|
||||
versuch++;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
// send an NTP request to the time server at the given address
|
||||
void sendNTPpacket(IPAddress& address) {
|
||||
//------------------------------------
|
||||
memset(packetBuf, 0, NTP_PACKET_SIZE); // set all bytes in the buffer to 0
|
||||
// Initialize values needed to form NTP request
|
||||
packetBuf[0] = B11100011; // LI, Version, Mode
|
||||
packetBuf[1] = 0; // Stratum
|
||||
packetBuf[2] = 6; // Max Interval between messages in seconds
|
||||
packetBuf[3] = 0xEC; // Clock Precision
|
||||
// bytes 4 - 11 are for Root Delay and Dispersion and were set to 0 by memset
|
||||
packetBuf[12] = 49; // four-byte reference ID identifying
|
||||
packetBuf[13] = 0x4E;
|
||||
packetBuf[14] = 49;
|
||||
packetBuf[15] = 52;
|
||||
// send the packet requesting a timestamp:
|
||||
Udp.beginPacket(address, 123); //NTP requests are to port 123
|
||||
Udp.write(packetBuf,NTP_PACKET_SIZE);
|
||||
Udp.endPacket();
|
||||
|
||||
}
|
||||
|
||||
int getTimeTrials = 0;
|
||||
|
||||
bool isValidDateTime (time_t no) {
|
||||
return (year(no) > 2020 && year(no) < 2038);
|
||||
}
|
||||
|
||||
bool isDayofDaylightChange (time_t local_t) {
|
||||
//-----------------------------------------
|
||||
int jahr = year (local_t);
|
||||
int monat = month (local_t);
|
||||
int tag = day (local_t);
|
||||
bool ret = ( (monat ==3 && tag == (31 - (5 * jahr /4 + 4) % 7)) ||
|
||||
(monat==10 && tag == (31 - (5 * jahr /4 + 1) % 7)));
|
||||
DEBUG_OUT.print ("isDayofDaylightChange="); DEBUG_OUT.println (ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
// calculates the daylight saving time for middle Europe. Input: Unixtime in UTC (!)
|
||||
// übernommen von Jurs, see : https://forum.arduino.cc/index.php?topic=172044.msg1278536#msg1278536
|
||||
time_t offsetDayLightSaving (uint32_t local_t) {
|
||||
//--------------------------------------------
|
||||
int monat = month (local_t);
|
||||
if (monat < 3 || monat > 10) return 0; // no DSL in Jan, Feb, Nov, Dez
|
||||
if (monat > 3 && monat < 10) return 1; // DSL in Apr, May, Jun, Jul, Aug, Sep
|
||||
int jahr = year (local_t);
|
||||
int std = hour (local_t);
|
||||
//int tag = day (local_t);
|
||||
int stundenBisHeute = (std + 24 * day(local_t));
|
||||
if ( (monat == 3 && stundenBisHeute >= (1 + timeZone + 24 * (31 - (5 * jahr /4 + 4) % 7))) ||
|
||||
(monat == 10 && stundenBisHeute < (1 + timeZone + 24 * (31 - (5 * jahr /4 + 1) % 7))) )
|
||||
return 1;
|
||||
else
|
||||
return 0;
|
||||
/*
|
||||
int stundenBisWechsel = (1 + 24 * (31 - (5 * year(local_t) / 4 + 4) % 7));
|
||||
if (monat == 3 && stundenBisHeute >= stundenBisWechsel || monat == 10 && stundenBisHeute < stundenBisWechsel)
|
||||
return 1;
|
||||
else
|
||||
return 0;
|
||||
*/
|
||||
}
|
||||
|
||||
|
||||
time_t getNow () {
|
||||
//---------------
|
||||
time_t jetzt = now();
|
||||
while (!isValidDateTime(jetzt) && getTimeTrials < 10) { // ungültig, max 10x probieren
|
||||
if (getTimeTrials) {
|
||||
//Serial.print (getTimeTrials);
|
||||
//Serial.println(". Versuch für getNtpTime");
|
||||
}
|
||||
jetzt = getNtpTime ();
|
||||
if (isValidDateTime(jetzt)) {
|
||||
setTime (jetzt);
|
||||
getTimeTrials = 0;
|
||||
}
|
||||
else
|
||||
getTimeTrials++;
|
||||
}
|
||||
//return jetzt + offsetDayLightSaving(jetzt)*SECS_PER_HOUR;
|
||||
return jetzt;
|
||||
}
|
||||
|
||||
|
||||
char _timestr[24];
|
||||
|
||||
char* getNowStr (time_t no = getNow()) {
|
||||
//------------------------------------
|
||||
sprintf (_timestr, "%02d:%02d:%02d", hour(no), minute(no), second(no));
|
||||
return _timestr;
|
||||
}
|
||||
|
||||
char* getTimeStr (time_t no = getNow()) {
|
||||
//------------------------------------
|
||||
return getNowStr (no);
|
||||
}
|
||||
|
||||
char* getDateTimeStr (time_t no) {
|
||||
//------------------------------
|
||||
sprintf (_timestr, "%04d-%02d-%02d+%02d:%02d:%02d", year(no), month(no), day(no), hour(no), minute(no), second(no));
|
||||
return _timestr;
|
||||
}
|
||||
|
||||
char* getDateStr (time_t no) {
|
||||
//------------------------------
|
||||
sprintf (_timestr, "%04d-%02d-%02d", year(no), month(no), day(no));
|
||||
return _timestr;
|
||||
}
|
||||
|
||||
|
||||
#endif
|
|
@ -64,7 +64,7 @@ const byteAssign_t hm400assignment[] = {
|
|||
{ FLD_IDC, UNIT_A, CH1, CMD01, 5, 2, 100 },
|
||||
{ FLD_PDC, UNIT_W, CH1, CMD01, 7, 2, 10 },
|
||||
{ FLD_YT, UNIT_KWH, CH1, CMD01, 9, 4, 1000 },
|
||||
{ FLD_YD, UNIT_WH, CH1, CMD01, 13, 2, 1000 },
|
||||
{ FLD_YD, UNIT_WH, CH1, CMD01, 13, 2, 1 },
|
||||
{ FLD_UAC, UNIT_V, CH0, CMD01, 15, 2, 10 },
|
||||
{ FLD_F, UNIT_HZ, CH0, CMD82, 1, 2, 100 },
|
||||
{ FLD_PAC, UNIT_W, CH0, CMD82, 3, 2, 10 },
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue