Compare commits

..

No commits in common. "master" and "203c388ae2d1deafed0c09b8597e0ff10bcfa4e9" have entirely different histories.

19 changed files with 702 additions and 585 deletions

View File

@ -2,6 +2,7 @@
// See http://go.microsoft.com/fwlink/?LinkId=827846 // See http://go.microsoft.com/fwlink/?LinkId=827846
// for the documentation about the extensions.json format // for the documentation about the extensions.json format
"recommendations": [ "recommendations": [
"ijustdev.gitea-vscode",
"platformio.platformio-ide" "platformio.platformio-ide"
], ],
"unwantedRecommendations": [ "unwantedRecommendations": [

View File

@ -1,6 +1,4 @@
{ {
"gitea.instanceURL": "https://hjkgitunix.dedyn.io/", "gitea.instanceURL": "https://hjkgitunix.dedyn.io/hans-jurgen/Wetterstation_Boris.git",
"gitea.owner": "hans-jurgen", "gitea.owner": "hans-jürgen"
"gitea.repo": "Wetterstation",
"gitea.token": " vscodegitea"
} }

View File

@ -1 +0,0 @@
1.02910

1
data/error.dat Normal file
View File

@ -0,0 +1 @@
0

View File

@ -1 +0,0 @@
5

View File

@ -1,39 +1,39 @@
This directory is intended for project header files. This directory is intended for project header files.
A header file is a file containing C declarations and macro definitions A header file is a file containing C declarations and macro definitions
to be shared between several project source files. You request the use of a to be shared between several project source files. You request the use of a
header file in your project source file (C, C++, etc) located in `src` folder header file in your project source file (C, C++, etc) located in `src` folder
by including it, with the C preprocessing directive `#include'. by including it, with the C preprocessing directive `#include'.
```src/main.c ```src/main.c
#include "header.h" #include "header.h"
int main (void) int main (void)
{ {
... ...
} }
``` ```
Including a header file produces the same results as copying the header file Including a header file produces the same results as copying the header file
into each source file that needs it. Such copying would be time-consuming into each source file that needs it. Such copying would be time-consuming
and error-prone. With a header file, the related declarations appear and error-prone. With a header file, the related declarations appear
in only one place. If they need to be changed, they can be changed in one in only one place. If they need to be changed, they can be changed in one
place, and programs that include the header file will automatically use the place, and programs that include the header file will automatically use the
new version when next recompiled. The header file eliminates the labor of new version when next recompiled. The header file eliminates the labor of
finding and changing all the copies as well as the risk that a failure to finding and changing all the copies as well as the risk that a failure to
find one copy will result in inconsistencies within a program. find one copy will result in inconsistencies within a program.
In C, the usual convention is to give header files names that end with `.h'. In C, the usual convention is to give header files names that end with `.h'.
It is most portable to use only letters, digits, dashes, and underscores in It is most portable to use only letters, digits, dashes, and underscores in
header file names, and at most one dot. header file names, and at most one dot.
Read more about using header files in official GCC documentation: Read more about using header files in official GCC documentation:
* Include Syntax * Include Syntax
* Include Operation * Include Operation
* Once-Only Headers * Once-Only Headers
* Computed Includes * Computed Includes
https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html

31
include/error.h Normal file
View File

@ -0,0 +1,31 @@
#include <Arduino.h>
#include <EEPROM.h>
#define AkkuLeer 0x80
#define ADS1115noReady 0x01
#define HTU21noReady 0x02
#define BMP280noReady 0x04
#define MCP9808noReady 0x08
byte SystemStatus;
void writeSystemStatus()
{
EEPROM.begin(512);
EEPROM.put(0,SystemStatus);
EEPROM.commit();
EEPROM.end();
}
void readSystemStatus()
{
EEPROM.begin(512);
EEPROM.get(0,SystemStatus);
EEPROM.commit();
EEPROM.end();
}

View File

@ -11,9 +11,12 @@ float valTemp;
// Create MCP9808 temperature sensor object // Create MCP9808 temperature sensor object
Adafruit_MCP9808 tempsensor = Adafruit_MCP9808(); Adafruit_MCP9808 tempsensor = Adafruit_MCP9808();
bool F_MCP9808;
char Temperature[15] = {0}; char Temperature[15] = {0};
void init_MCP9808(){ void init_MCP9808(){
F_MCP9808 = true;
// Make sure the sensor is found, you can also pass in a different i2c // Make sure the sensor is found, you can also pass in a different i2c
// address with tempsensor.begin(0x19) for example, also can be left in blank for default address use // address with tempsensor.begin(0x19) for example, also can be left in blank for default address use
// Also there is a table with all addres possible for this sensor, you can connect multiple sensors // Also there is a table with all addres possible for this sensor, you can connect multiple sensors
@ -29,10 +32,12 @@ void init_MCP9808(){
// 1 1 1 0x1F // 1 1 1 0x1F
if (!tempsensor.begin(0x18)) { if (!tempsensor.begin(0x18)) {
Serial.println("Couldn't find MCP9808! Check your connections and verify the address is correct."); Serial.println("Couldn't find MCP9808! Check your connections and verify the address is correct.");
datenSave(-20); SystemStatus = SystemStatus | MCP9808noReady;
while (1); F_MCP9808 = false;
} else {
Serial.println("Found MCP9808!");
} }
Serial.println("Found MCP9808!");
tempsensor.setResolution(3); // sets the resolution mode of reading, the modes are defined in the table bellow: tempsensor.setResolution(3); // sets the resolution mode of reading, the modes are defined in the table bellow:
// Mode Resolution SampleTime // Mode Resolution SampleTime
// 0 0.5°C 30 ms // 0 0.5°C 30 ms

View File

@ -20,6 +20,7 @@
* ADS1115_WE adc = ADS1115_WE(&Wire, I2C_ADDRESS); -> all together * ADS1115_WE adc = ADS1115_WE(&Wire, I2C_ADDRESS); -> all together
*/ */
ADS1115_WE adc = ADS1115_WE(I2C_ADDRESS); ADS1115_WE adc = ADS1115_WE(I2C_ADDRESS);
bool F_ADS1115;
struct { struct {
char Akku[15] = {0}; char Akku[15] = {0};
@ -28,8 +29,11 @@ struct {
void initADS() { void initADS() {
Wire.begin(); Wire.begin();
F_ADS1115 = true;
if(!adc.init()){ if(!adc.init()){
Serial.println("ADS1115 not connected!"); Serial.println("ADS1115 not connected!");
SystemStatus = (SystemStatus | ADS1115noReady);
F_ADS1115 = false;
} }
/* Set the voltage range of the ADC to adjust the gain /* Set the voltage range of the ADC to adjust the gain

87
include/mess_BME280.h Normal file
View File

@ -0,0 +1,87 @@
#include "Wire.h"
#define Anzahl_Sensoren_BME280 1 // Mögliche Werte: '0','1','2'
#define Korrektur_Luftdruck 0.0 // Korrekturwert um Abweichungen zu offiziellen Wetterstationen auszugleichen
//----------------------------------------------------------------
// Konfiguration BME280 - Temperatur und Luftfeuchte
//----------------------------------------------------------------
#include "Adafruit_Sensor.h"
#include "Adafruit_BME280.h"
uint8_t BME280_adresse[2] = {0x76, 0x77};
#define SEALEVELPRESSURE_HPA (1013.25f)
//----------------------------------------------------------------
const float No_Val = 999.99;
float Temp[2] = {No_Val, No_Val};
float Feuchte[2] = {No_Val, No_Val};
float L_Druck[2] = {No_Val, No_Val};
struct {
char temperature[15] = {0};
char pressure[15] = {0};
char approx_altitud[15] = {0};
char humity[15] = {0};
} BME280Data;
void Sensor_BME280() {
if (Anzahl_Sensoren_BME280 > 0) {
float Temperatur_BME;
float Luftfeuchte_BME;
float Luftdruck_BME;
boolean check;
Adafruit_BME280 my_bme;
for (byte i = 0; i < Anzahl_Sensoren_BME280; i++) {
check = my_bme.begin(BME280_adresse[i]); // I2C Adresse
delay (100); // time to get system ready
if (check) { // if bme ok
Temperatur_BME = my_bme.readTemperature();
Luftfeuchte_BME = my_bme.readHumidity();
Luftdruck_BME = my_bme.readPressure();
Serial.print("Temperature (BME280):\t\t");
Serial.print(Temperatur_BME);
Serial.println(" °C");
Serial.print("Luftfeuchtigkeit (BME280):\t");
Serial.print(Luftfeuchte_BME);
Serial.println(" %");
Serial.print("Luftdruck (BME280):\t\t");
Serial.print(Luftdruck_BME/100);
Serial.println(" hPa");
}
else {
Temperatur_BME = No_Val;
Luftfeuchte_BME = No_Val;
Luftdruck_BME = No_Val;
}
if (i == 0) { // erster BME
Temp[0] = Temperatur_BME; // Hier kann die Zuordnung der Sensoren geändert werden
Feuchte[0] = Luftfeuchte_BME; // Hier kann die Zuordnung der Sensoren geändert werden
L_Druck[0] = Luftdruck_BME/100;
}
if (i == 1) { // zweiter BME
Temp[1] = Temperatur_BME; // Hier kann die Zuordnung der Sensoren geändert werden
Feuchte[1] = Luftfeuchte_BME; // Hier kann die Zuordnung der Sensoren geändert werden
L_Druck[1] = Luftdruck_BME/100;
}
}
}
}
void M2M_BME280(String deviceId = "4711") {
char topic[100];
dtostrf(Temp[0],7,1,BME280Data.temperature);
sprintf(topic, "%s%s%s", "hjk/devices/", deviceId.c_str(), "/telemetry/temperature_BME_280" );
client.publish(topic, BME280Data.temperature, true);
dtostrf(Feuchte[0],7,1,BME280Data.humity);
sprintf(topic, "%s%s%s", "hjk/devices/", deviceId.c_str(), "/telemetry/humity_BME280" );
client.publish(topic, BME280Data.humity, true);
dtostrf(L_Druck[0],7,1,BME280Data.pressure);
sprintf(topic, "%s%s%s", "hjk/devices/", deviceId.c_str(), "/telemetry/pressure" );
client.publish(topic, BME280Data.pressure, true);
}

View File

@ -4,12 +4,12 @@
#include <Adafruit_BMP280.h> #include <Adafruit_BMP280.h>
#define SEALEVELPRESSURE_HPA (1002.7) // 1013.25 #define SEALEVELPRESSURE_HPA (1013.25) // 1013.25
// Richen 219 m über NN // Richen 219 m über NN
// Eppingem 195 m über NN // Eppingem 195 m über NN
Adafruit_BMP280 bmp; // I2C Adafruit_BMP280 bmp; // I2C
float K_BMP280 = -1.30; float K_BMP280 = -0.0;
bool F_BMP280; bool F_BMP280;
@ -23,14 +23,15 @@ struct {
void Init_BMP280(){ void Init_BMP280(){
bool status = bmp.begin(0x76); bool status = bmp.begin();
F_BMP280 = true; F_BMP280 = true;
if (!status) { if (!status) {
Serial.println("Could not find a valid BME280 sensor, check wiring!"); Serial.println("Could not find a valid BME280 sensor, check wiring!");
F_BMP280 = false; F_BMP280 = false;
SystemStatus = SystemStatus | BMP280noReady;
} else{ } else{
/* Serial.print("SensorID was: 0x"); Serial.println(bmp.sensorID(),16); Serial.print("SensorID was: 0x"); Serial.println(bmp.sensorID(),16);
delay(5000); */ delay(5000);
/* Default settings from datasheet. */ /* Default settings from datasheet. */
bmp.setSampling(Adafruit_BMP280::MODE_NORMAL, /* Operating Mode. */ bmp.setSampling(Adafruit_BMP280::MODE_NORMAL, /* Operating Mode. */
Adafruit_BMP280::SAMPLING_X2, /* Temp. oversampling */ Adafruit_BMP280::SAMPLING_X2, /* Temp. oversampling */
@ -55,8 +56,8 @@ void read_BMP_280() {
Serial.print("Pressure:\t\t"); Serial.print("Pressure:\t\t");
float p = bmp.readPressure() / 100.0F; float p = bmp.readPressure() / 100.0F;
//p = p + 22; p = p + KorrekturLuftdruck;
dtostrf(p,5,0,BMP280Data.pressure); dtostrf(p,7,1,BMP280Data.pressure);
Serial.print(BMP280Data.pressure); Serial.print(BMP280Data.pressure);
Serial.println(" hPa"); Serial.println(" hPa");

View File

@ -1,9 +1,8 @@
#include <Arduino.h> #include <Arduino.h>
ADC_MODE(ADC_VCC);
const float MinimalSpannung = 2.85; const float MinimalSpannung = 2.85;
float korectur = 9.2800899887514060742407199100112e-4; float korectur = 0.001015;
char floatString[15] = {0}; char floatString[15] = {0};
float AKKU; float AKKU;
@ -13,10 +12,11 @@ float getBattery()
Serial.print("Batterie:\t\t 3.05 V\n"); Serial.print("Batterie:\t\t 3.05 V\n");
return 3.05; return 3.05;
#endif #endif
int Vcc = ESP.getVcc(); int Vcc = analogRead(A0);
Vcc = Vcc * ((100+220+220)/100);
float VCC = Vcc * korectur ; float VCC = Vcc * korectur ;
Serial.printf("Rohdaten: %d, ", Vcc); Serial.printf("Rohdaten: %d, ", Vcc);
dtostrf(VCC,7,2,floatString); dtostrf(VCC,8,2,floatString);
Serial.printf("Vcc: %s V\n", floatString); Serial.printf("Vcc: \t%s V\n", floatString);
return VCC; return VCC;
} }

View File

@ -1,7 +1,7 @@
#include <Arduino.h> #include <Arduino.h>
const float MinimalSpannung = 2.85; const float MinimalSpannung = 2.85;
float korectur = 1.02910; float koa = 0.984326019;
char floatString[15] = {0}; char floatString[15] = {0};
float AKKU; float AKKU;

View File

@ -6,7 +6,7 @@
Adafruit_HTU21DF htu = Adafruit_HTU21DF(); Adafruit_HTU21DF htu = Adafruit_HTU21DF();
bool F_HTU_21D; bool F_HTU_21D;
float K_HTU= -1.30; float K_HTU= -0.00;
struct { struct {
char temperature[15] = {0}; char temperature[15] = {0};
@ -17,10 +17,13 @@ void init_HTU21(){
F_HTU_21D = false; F_HTU_21D = false;
if (!htu.begin()) { if (!htu.begin()) {
Serial.println("Couldn't find sensor HUT21D!"); Serial.println("Couldn't find sensor HUT21D!");
SystemStatus = SystemStatus | HTU21noReady;
} }
F_HTU_21D = true; else {
Serial.println("HUT21D gefunden"); F_HTU_21D = true;
Serial.println("HUT21D gefunden");
}
} }
void read_HTU21D() { void read_HTU21D() {

View File

@ -1,46 +1,46 @@
This directory is intended for project specific (private) libraries. This directory is intended for project specific (private) libraries.
PlatformIO will compile them to static libraries and link into executable file. PlatformIO will compile them to static libraries and link into executable file.
The source code of each library should be placed in a an own separate directory The source code of each library should be placed in a an own separate directory
("lib/your_library_name/[here are source files]"). ("lib/your_library_name/[here are source files]").
For example, see a structure of the following two libraries `Foo` and `Bar`: For example, see a structure of the following two libraries `Foo` and `Bar`:
|--lib |--lib
| | | |
| |--Bar | |--Bar
| | |--docs | | |--docs
| | |--examples | | |--examples
| | |--src | | |--src
| | |- Bar.c | | |- Bar.c
| | |- Bar.h | | |- Bar.h
| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html | | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html
| | | |
| |--Foo | |--Foo
| | |- Foo.c | | |- Foo.c
| | |- Foo.h | | |- Foo.h
| | | |
| |- README --> THIS FILE | |- README --> THIS FILE
| |
|- platformio.ini |- platformio.ini
|--src |--src
|- main.c |- main.c
and a contents of `src/main.c`: and a contents of `src/main.c`:
``` ```
#include <Foo.h> #include <Foo.h>
#include <Bar.h> #include <Bar.h>
int main (void) int main (void)
{ {
... ...
} }
``` ```
PlatformIO Library Dependency Finder will find automatically dependent PlatformIO Library Dependency Finder will find automatically dependent
libraries scanning project source files. libraries scanning project source files.
More information about PlatformIO Library Dependency Finder More information about PlatformIO Library Dependency Finder
- https://docs.platformio.org/page/librarymanager/ldf.html - https://docs.platformio.org/page/librarymanager/ldf.html

View File

@ -1,65 +1,120 @@
; PlatformIO Project Configuration File ; PlatformIO Project Configuration File
; ;
; Build options: build flags, source filter ; Build options: build flags, source filter
; Upload options: custom upload port, speed and extra flags ; Upload options: custom upload port, speed and extra flags
; Library options: dependencies, extra library storages ; Library options: dependencies, extra library storages
; Advanced options: extra scripting ; Advanced options: extra scripting
; ;
; Please visit documentation for the other options and examples ; Please visit documentation for the other options and examples
; https://docs.platformio.org/page/projectconf.html ; https://docs.platformio.org/page/projectconf.html
[env] [env]
platform = espressif8266 platform = espressif8266
board = d1 board = d1
framework = arduino framework = arduino
monitor_port = /dev/ttyUSB0 board_build.filesystem = littlefs
monitor_speed = 74800 monitor_port = COM5
monitor_filters = time monitor_speed = 74800
board_build.filesystem = littlefs monitor_filters = time
lib_deps = upload_port = COM5
knolleary/PubSubClient @ 2.8 lib_deps =
adafruit/Adafruit HTU21DF Library @ 1.0.5 knolleary/PubSubClient @ 2.8
adafruit/Adafruit BMP280 Library @ 2.6.6 adafruit/Adafruit HTU21DF Library @ 1.0.5
wollewald/ADS1115_WE @ 1.4.3 wollewald/ADS1115_WE @ 1.4.3
adafruit/Adafruit MCP9808 Library @ 2.0.0 adafruit/Adafruit MCP9808 Library @ 2.0.0
adafruit/Adafruit BusIO @ 1.16.1
build_flags = adafruit/Adafruit BME280 Library @ 2.2.4
-DTEMPTEST33=1 adafruit/Adafruit Unified Sensor @ 1.1.14
-DNOBATT=0
-DMaxErrCount=30 build_flags =
-DMQTT=0 -DTEMPTEST33=1
-DNOBATT=0
-DMaxErrCount=20
[env:debug] ; Entwicklungssystem
build_flags = ${env.build_flags}
-DDEBUG=0 [env:debug] ; Entwicklungssystem
-DNOADS=0 build_flags = ${env.build_flags}
-DNAME=\"WETTERSTATIONEPPINGEN\" -DDEBUG=0
-DSTASSID=\"St.-Peters-Gasse\" -DNOADS=0
-DSTAPSK=\"1952994784599318\" -DNAME=\"WETTERSTATION\"
-DGATEWAY=\"192.168.127.1\" -DSTASSID=\"MagentaWLAN-RGDO\"
-DDNS=\"192.168.127.1\" -DSTAPSK=\"93329248424922704583\"
-DKMYIP=\"192.168.127.48\" -DGATEWAY=\"192.168.127.1\"
-Dmqtt_server=\"hjkmqtt.dedyn.io\" -DDNS=\"192.168.127.1\"
-Dmqtt_port=8883 -DKMYIP=\"192.168.127.40\"
-DTERROR=5 -Dmqtt_server=\"hjkmqtt.dedyn.io\"
-DTLOWBATT=60 -Dmqtt_port=61883
-DTINTERVAL=1 -DTERROR=5
-DTLOWBATT=60
[env:release] ; Produktivsystem: -DTINTERVAL=1
build_flags = ${env.build_flags} -DKorrekturLuftdruck=0.0
-DDEBUG=0
-DEMAIL=\"koerner.c.m@gmail.com\" [env:marcel] ; Produktivsystem:
-DNAME=\"WETTERSTATIONMARCEL\" build_flags = ${env.build_flags}
-DSTASSID=\"EasyBox-838169\" -DDEBUG=0
-DSTAPSK=\"RcZmua6Xv4R4V5Kf\" -DEMAIL=\"koerner.c.m@gmail.com\"
-DGATEWAY=\"192.168.2.1\" -DNAME=\"WETTERSTATIONMARCEL\"
-DDNS=\"192.168.2.1\" -DSTASSID=\"EasyBox-838169\"
-DKMYIP=\"192.168.2.81\" -DSTAPSK=\"RcZmua6Xv4R4V5Kf\"
-Dmqtt_server=\"hjkmqtt.dedyn.io\" -DGATEWAY=\"192.168.2.1\"
-Dmqtt_port=8883 -DDNS=\"192.168.2.1\"
-DTERROR=20 -DKMYIP=\"192.168.2.81\"
-DTLOWBATT=60 -Dmqtt_server=\"hjkmqtt.dedyn.io\"
-DTINTERVAL=10 -Dmqtt_port=8883
-DTERROR=20
-DTLOWBATT=60
-DTINTERVAL=10
-DKorrekturLuftdruck=0.0
[env:boris] ; Produktivsystem:
build_flags = ${env.build_flags}
-DDEBUG=0
-DEMAIL=\"koerner.c.m@gmail.com\"
-DNAME=\"WETTERSTATIONBORIS\"
-DSTASSID=\"FRITZ!Box7362SL\"
-DSTAPSK=\"BorisundEva2007\"
-DGATEWAY=\"192.168.2.1\"
-DDNS=\"192.168.2.1\"
-DKMYIP=\"192.168.2.41\"
-Dmqtt_server=\"hjkmqtt.dedyn.io\"
-Dmqtt_port=8883
-DTERROR=20
-DTLOWBATT=60
-DTINTERVAL=5
-DKorrekturLuftdruck=0.0
[env:hjk]
build_flags = ${env.build_flags}
-DDEBUG=0
-DNOADS=0
-DNAME=\"WETTERSTATION\"
-DSTASSID=\"MagentaWLAN-RGDO\"
-DSTAPSK=\"93329248424922704583\"
-DGATEWAY=\"192.168.127.1\"
-DDNS=\"192.168.127.1\"
-DKMYIP=\"192.168.127.41\"
-Dmqtt_server=\"hjkmqtt.dedyn.io\"
-Dmqtt_port=61883
-DTERROR=5
-DTLOWBATT=60
-DTINTERVAL=10
-DKorrekturLuftdruck=23.6
[env:filamentbox]
build_flags = ${env.build_flags}
-DDEBUG=0
-DNOADS=0
-DNAME=\"filamenbox\"
-DSTASSID=\"MagentaWLAN-RGDO\"
-DSTAPSK=\"93329248424922704583\"
-DGATEWAY=\"192.168.127.1\"
-DDNS=\"192.168.127.1\"
-DKMYIP=\"192.168.127.42\"
-Dmqtt_server=\"hjkmqtt.dedyn.io\"
-Dmqtt_port=61883
-DTERROR=5
-DTLOWBATT=60
-DTINTERVAL=15
-DKorrekturLuftdruck=0.0

View File

@ -1,394 +1,331 @@
#include <Arduino.h> #include <Arduino.h>
#include <FS.h> //this needs to be first, or it all crashes and burns... #include <FS.h> //this needs to be first, or it all crashes and burns...
#include <LittleFS.h> #include <string>
#include <string> #include <ESP8266WiFi.h> //https://github.com/esp8266/Arduino
#include <ESP8266WiFi.h> //https://github.com/esp8266/Arduino #include <PubSubClient.h>
#include <PubSubClient.h> #include <Ticker.h>
#include <Ticker.h>
// #define BUILTIN_LED D2
#define BUILTIN_LED D15 #define TRIGGER_PIN D7
#define TRIGGER_PIN D7 #define START_STOP_PIN D6
#define START_STOP_PIN D6
void reconnect();
void reconnect(); void setup_wifi();
void setup_wifi();
void datenSave(int wert); void verifyFingerprint();
int readDaten(); void callback(char* topic1, byte* payload, unsigned int length);
int saveKorektur(float wert); void pulse_pin(uint8_t pin);
float readKorectur();
void verifyFingerprint(); WiFiClient espClient;
void callback(char* topic1, byte* payload, unsigned int length); PubSubClient client(espClient);
void pulse_pin(uint8_t pin);
#include <error.h>
WiFiClientSecure espClient;
PubSubClient client(espClient); #include<mess_htu21.h>
#include<mess_htu21.h> //#include <mess_BMP280.h>
#include <mess_BME280.h>
#include <mess_BMP280.h>
#include <mess_Ub.h>
#include <mess_Ub.h>
#include <messADS1115.h>
#include <messADS1115.h>
#include <mcp9808.h>
#include <mcp9808.h>
const char* ssid = STASSID; const char* ssid = STASSID;
const char* password = STAPSK; const char* password = STAPSK;
String hostname = NAME; String hostname = NAME;
const char *MyIP = KMYIP; const char *MyIP = KMYIP;
IPAddress ip; IPAddress ip;
IPAddress gateway; IPAddress gateway;
IPAddress subnet(255, 255, 255, 0); IPAddress subnet(255, 255, 255, 0);
IPAddress dns; IPAddress dns;
IPAddress secondaryDNS(8, 8, 8, 8); IPAddress secondaryDNS(8, 8, 8, 8);
const char* mqtt_fprint = "a3:44:1d:aa:6e:e5:c7:55:02:20:98:ea:9b:df:1a:42:a2:f3:e3:0d"; const char* mqtt_fprint = "a3:44:1d:aa:6e:e5:c7:55:02:20:98:ea:9b:df:1a:42:a2:f3:e3:0d";
const char* mqtt_user = "mqtt"; const char* mqtt_user = "mqtt";
const char* mqtt_pass = "fische"; const char* mqtt_pass = "fische";
const unsigned long interval = TINTERVAL * 60000000LU; // Minuten * Mikrosekunden für Sleep Mode const unsigned long interval = TINTERVAL * 60000000LU; // Minuten * Mikrosekunden für Sleep Mode
const unsigned long intervalLowBatt = TLOWBATT * 60000000LU; // Minuten * Mikrosekunden für Sleep Mode, Akku entladen const unsigned long intervalLowBatt = TLOWBATT * 60000000LU; // Minuten * Mikrosekunden für Sleep Mode, Akku entladen
const unsigned long stoerung = TERROR * 60000000LU; // Minuten * Mikrosekunden für Sleep Mode const unsigned long stoerung = TERROR * 60000000LU; // Minuten * Mikrosekunden für Sleep Mode
unsigned long previousMillis = 0; unsigned long previousMillis = 0;
long deviceId; long deviceId;
char sID[16]; char sID[16];
char clientName[30]; char clientName[30];
unsigned long startTime; unsigned long startTime;
unsigned long endTime; unsigned long endTime;
char topic[100]; char topic[100];
char topic_1[50]; char topic_1[50];
char topicWert[20]; char topicWert[20];
char msg[20]; char msg[20];
int SystemStatus; long int Feldstaerke;
void setup() { void setup() {
pinMode(TRIGGER_PIN, OUTPUT); startTime = millis();
pinMode(START_STOP_PIN, OUTPUT); /* pinMode(BUILTIN_LED, OUTPUT);
digitalWrite(TRIGGER_PIN, HIGH); digitalWrite(BUILTIN_LED, LOW);
digitalWrite(START_STOP_PIN, LOW); delay(5000);
pulse_pin(TRIGGER_PIN); // ==> 1 digitalWrite(BUILTIN_LED, HIGH); */
Serial.begin(74880); Serial.begin(74880);
while ( !Serial ) delay(100); // wait for native usb while ( !Serial ) delay(100); // wait for native usb
Serial.println(F("BMP280 Sensor event test")); WiFi.mode( WIFI_OFF );
Serial.println("HTU21D-F test"); WiFi.forceSleepBegin();
startTime = millis(); Serial.println();
WiFi.mode( WIFI_OFF );
WiFi.forceSleepBegin(); Serial.println();
pulse_pin(TRIGGER_PIN); // ==> 1 Serial.println();
Serial.println(); Serial.println();
//Serial.println("Testpunkt 1"); readSystemStatus();
/* if (!LittleFS.begin()) { Serial.printf("Systemstatus : 0x%02x \n", SystemStatus);
Serial.println("LittleFS mount failed"); SystemStatus = 0x00;
delay(5000); writeSystemStatus();
return; delay(500);
} */ #if (MQTT == 0)
//Serial.println("Testpunkt 2"); init_HTU21();
/* Dir dir = LittleFS.openDir("/data"); //Init_BMP280();
while (dir.next()) { Sensor_BME280();
Serial.print(dir.fileName());
if(dir.fileSize()) { init_MCP9808();
File f = dir.openFile("r"); initADS();
Serial.println(f.size()); #endif
} if (!F_ADS1115 == true){
} */ AKKU = getBattery(); // ca. 170 ms
//Serial.println("Testpunkt 3"); Serial.println("ALTE UB MESSUNG:");
Serial.println(); }
Serial.println(); else{
Serial.println(); MessungADS();
//SystemStatus = readDaten(); AKKU = readChannel(ADS1115_COMP_0_GND);
//korectur = readKorectur(); }
//Serial.print("Korektur: "); Serial.println(korectur,6); // ca. 280 ms
pinMode(BUILTIN_LED, OUTPUT); // Initialize the BUILTIN_LED pin as an output if (F_HTU_21D == true){
//digitalWrite(BUILTIN_LED, LOW); read_HTU21D();
//digitalWrite(BUILTIN_LED, HIGH); }
//Serial.print("STATUS (Systemmeldung): "); Serial.println(SystemStatus); if (F_ADS1115 == true){
#if (MQTT == 0) MessungADS();
init_HTU21(); }
Init_BMP280(); /* if (F_BMP280 == true){
//initADS(); read_BMP_280();
//init_MCP9808(); }*/
#endif if (F_MCP9808 == true){
AKKU = getBattery(); // ca. 170 ms valTemp = getTemperature_MCP9808();
// ca. 280 ms }
if (F_HTU_21D == true){ setup_wifi(); // ca. 4,5 s
read_HTU21D(); deviceId = ESP.getChipId();
} sprintf(sID, "%010ld", deviceId);
read_BMP_280(); Serial.print("ID: \t\t"); Serial.println(deviceId);
//MessungADS();
setup_wifi(); // ca. 4,5 s // ca. 5 s
// ca. 12ms //espClient.setFingerprint(mqtt_fprint);
// --------------------------------- client.setServer(mqtt_server, mqtt_port);
// Status ändern !!! 0 client.setCallback(callback);
//datenSave(0); Serial.printf("Systemstatus : 0x%02x \n", SystemStatus);
// --------------------------------- //----------
//digitalWrite(BUILTIN_LED, HIGH);
deviceId = ESP.getChipId(); }
sprintf(sID, "%010ld", deviceId);
Serial.print("ID: \t\t"); Serial.println(deviceId); void loop() {
unsigned long Pause = 0;
// ca. 5 s if (!client.connected()) {
espClient.setFingerprint(mqtt_fprint); reconnect();
client.setServer(mqtt_server, mqtt_port); }
client.setCallback(callback); int currentMillis = millis();
//---------- if (currentMillis - previousMillis >= 10000) {
previousMillis = currentMillis;
} dtostrf(AKKU,8,2,ADSData.Akku);
sprintf(topic, "%s%s%s", "hjk/devices/", hostname.c_str(), "/telemetry/battery" );
void loop() { client.publish(topic, ADSData.Akku, true);
unsigned long Pause = 0; if (F_ADS1115 == true){
if (!client.connected()) { sprintf(topic, "%s%s%s", "hjk/devices/", hostname.c_str(), "/telemetry/Solar" );
reconnect(); client.publish(topic, ADSData.Solar, true);
} }
//client.loop();
int currentMillis = millis(); if (F_HTU_21D) M2M_HTU21D(hostname.c_str());
if (currentMillis - previousMillis >= 10000) { M2M_BME280(hostname.c_str());
previousMillis = currentMillis; if (F_MCP9808) M2M_Temperatur_MCP9808(hostname.c_str());
read_HTU21D(); sprintf(msg,"%ld", Feldstaerke);
read_BMP_280(); sprintf(topic, "%s%s%s", "hjk/devices/", hostname.c_str(), "/telemetry/RSSI" );
//valTemp = getTemperature_MCP9808(); client.publish(topic, msg, true);
dtostrf(AKKU,8,2,ADSData.Akku); sprintf(msg,"0x%02x", SystemStatus);
sprintf(topic, "%s%s%s", "hjk/devices/", hostname.c_str(), "/telemetry/battery" ); sprintf(topic, "%s%s%s", "hjk/devices/", hostname.c_str(), "/telemetry/SystemStatus" );
client.publish(topic, ADSData.Akku, true); client.publish(topic, msg, true);
#if(MQTT == 0) client.loop();
M2M_HTU21D(hostname.c_str()); delay(500);
M2M_BMP280(hostname.c_str()); //digitalWrite(BUILTIN_LED, HIGH);
M2M_Temperatur_MCP9808(hostname.c_str()); /* ESP.deepSleep(5e6);
#endif delay(100); */
long int Feldstaerke = WiFi.RSSI(); endTime = millis();
sprintf(msg,"%ld", Feldstaerke); if (AKKU < MinimalSpannung){
sprintf(topic, "%s%s%s", "hjk/devices/", hostname.c_str(), "/telemetry/RSSI" );
client.publish(topic, msg, true); // ---------------------------------
client.loop(); Pause = intervalLowBatt -((endTime - startTime) * 1000); // Pause ca. 60 Minuten
delay(500); Serial.println("AKKU entladen!");
digitalWrite(BUILTIN_LED, HIGH); SystemStatus = (SystemStatus | AkkuLeer);
/* ESP.deepSleep(5e6); Serial.printf("Systemstatus : 0x%04x \n", SystemStatus);
delay(100); */ writeSystemStatus();
endTime = millis(); }
if (AKKU < MinimalSpannung){ else{
// --------------------------------- Pause = interval -((endTime - startTime) * 1000); // Pause ca. 15 Minuten
// Status ändern !!! -5 }
datenSave(-5); if(Pause <=0){
// --------------------------------- Pause = 1;
Pause = intervalLowBatt -((endTime - startTime) * 1000); // Pause ca. 60 Minuten }
Serial.println("AKKU entladen!"); //ESP.restart();
} Serial.print("Ich gehe für ca. "); Serial.print((Pause/1000/1000/60)+1); Serial.println( " Minuten schlafen.");
else{ //ESP.deepSleep(Pause, WAKE_RF_DISABLED); // Pause
Pause = interval -((endTime - startTime) * 1000); // Pause ca. 15 Minuten digitalWrite(START_STOP_PIN, !LOW);
} #if (DEBUG == 1)
if(Pause <=0){ ESP.deepSleep(10e6);
Pause = 1; #else
} writeSystemStatus();
//ESP.restart(); ESP.deepSleep(Pause);
Serial.print("Ich gehe für ca. "); Serial.print((Pause/1000/1000/60)+1); Serial.println( " Minuten schlafen."); #endif
//ESP.deepSleep(Pause, WAKE_RF_DISABLED); // Pause
digitalWrite(START_STOP_PIN, !LOW); delay(100);
#if (DEBUG == 1) }
ESP.deepSleep(10e6); }
#else
ESP.deepSleep(Pause); void setup_wifi() {
#endif
long ErrCount = 0;
delay(100);
} delay(10);
} // We start by connecting to a WiFi network
Serial.println();
void setup_wifi() { Serial.print("Connecting to ");
Serial.print(ssid);
long ErrCount = 0; Serial.print(" ");
delay(10); WiFi.forceSleepWake();
// We start by connecting to a WiFi network delay( 1 );
Serial.println(); WiFi.persistent( false );
Serial.print("Connecting to "); WiFi.mode( WIFI_STA );
Serial.print(ssid); WiFi.setHostname(hostname.c_str()); //define hostname
Serial.print(" "); WiFi.hostname(hostname.c_str());
WiFi.mode( WIFI_STA );
WiFi.forceSleepWake(); if (!ip.fromString(MyIP)) { // try to parse into the IPAddress
delay( 1 ); Serial.println("UnParsable IP");
WiFi.persistent( false ); }
WiFi.mode( WIFI_STA ); if (!dns.fromString(DNS)) { // try to parse into the IPAddress
//WiFi.setHostname(hostname.c_str()); //define hostname Serial.println("UnParsable DNS");
WiFi.hostname(hostname.c_str()); }
WiFi.mode( WIFI_STA ); if (!gateway.fromString(GATEWAY)) { // try to parse into the IPAddress
if (!ip.fromString(MyIP)) { // try to parse into the IPAddress Serial.println("UnParsable GATEWAY");
Serial.println("UnParsable IP"); }
} //WiFi.config( ip, dns, gateway, subnet );
if (!dns.fromString(DNS)) { // try to parse into the IPAddress if (!WiFi.config(ip, gateway, subnet, dns, secondaryDNS))
Serial.println("UnParsable DNS"); {
} Serial.println("STA Failed to configure");
if (!gateway.fromString(GATEWAY)) { // try to parse into the IPAddress }
Serial.println("UnParsable GATEWAY");
} WiFi.begin(ssid, password);
//WiFi.config( ip, dns, gateway, subnet );
if (!WiFi.config(ip, gateway, subnet, dns, secondaryDNS)) while (WiFi.status() != WL_CONNECTED) {
{ delay(500);
Serial.println("STA Failed to configure"); Serial.print(".");
} ErrCount ++;
if (ErrCount >= MaxErrCount){
WiFi.begin(ssid, password); endTime = millis();
unsigned long Pause = stoerung -((endTime - startTime) * 1000); // Pause
while (WiFi.status() != WL_CONNECTED) { Serial.println();
delay(500); Serial.println("STÖRUNG WiFi.");
Serial.print("."); Serial.print("Ich gehe für ca. "); Serial.print(Pause/1000/1000/60); Serial.println( " Minuten schlafen.");
ErrCount ++; ESP.deepSleep(Pause, WAKE_NO_RFCAL); // Pause
if (ErrCount >= MaxErrCount){ delay(100);
// --------------------------------- }
// Status ändern !!! -1 }
datenSave(-1); Serial.println(" WiFi connected");
// --------------------------------- Serial.print("IP address: \t");
endTime = millis(); Feldstaerke = WiFi.RSSI();
unsigned long Pause = stoerung -((endTime - startTime) * 1000); // Pause Serial.print(WiFi.localIP()); Serial.print("\tRESSI: "); Serial.println(Feldstaerke);
Serial.println(); /* delay(2000);
Serial.println("STÖRUNG WiFi."); ESP.deepSleep(2e6, WAKE_RF_DEFAULT);
Serial.print("Ich gehe für ca. "); Serial.print(Pause/1000/1000/60); Serial.println( " Minuten schlafen."); delay(100); */
ESP.deepSleep(Pause, WAKE_NO_RFCAL); // Pause }
delay(100);
} void callback(char* topic1, byte* payload, unsigned int length)
} {
Serial.println(" WiFi connected"); Serial.print("Message arrived [");
Serial.print("IP address: \t"); Serial.print(topic1);
Serial.print(WiFi.localIP()); Serial.print("\tRESSI: "); Serial.println(WiFi.RSSI()); Serial.print("] ");
/* delay(2000); for (unsigned int i = 0; i < length; i++) {
ESP.deepSleep(2e6, WAKE_RF_DEFAULT); msg[i] = (char)payload[i];
delay(100); */ }
} msg[length] = '\0';
Serial.println(msg);
void callback(char* topic1, byte* payload, unsigned int length) if(strcmp(topic1, topic_1)== 0){
{ Serial.print(msg);
Serial.print("Message arrived ["); Serial.println();
Serial.print(topic1); korectur = atof(msg);
Serial.print("] "); Serial.print("Korektur:\t");Serial.println(korectur, 8);
for (unsigned int i = 0; i < length; i++) { }
msg[i] = (char)payload[i]; }
}
msg[length] = '\0'; void reconnect() {
Serial.println(msg); // Loop until we're reconnected
if(strcmp(topic1, topic_1)== 0){ sprintf(clientName, "%s%s", "ESP8266Wetter", sID);
Serial.print(msg); while (!client.connected()) {
Serial.println(); Serial.print("Attempting MQTT connection...");
korectur = atof(msg); //verifyFingerprint();
Serial.print("Korektur:\t");Serial.println(korectur, 8); // Attempt to connect
int er = saveKorektur(korectur); if (client.connect(clientName)) {
if (er != 0){ Serial.println("connected");
Serial.println("Daten konnten nicht gespeichert werden."); // Once connected, publish an announcement...
} // client.publish("outTopic", "hello world");
float test = readKorectur(); // ... and resubscribe
Serial.print("Korektur:\t");Serial.println(test, 8); // client.subscribe("inTopic");
} } else {
} Serial.print("failed, rc=");
Serial.print(client.state());
void reconnect() { Serial.println(" try again in 5 seconds");
// Loop until we're reconnected // Wait 5 seconds before retrying
sprintf(clientName, "%s%s", "ESP8266Client", sID); delay(5000);
while (!client.connected()) { ESP.restart();
Serial.print("Attempting MQTT connection..."); }
verifyFingerprint(); }
// Attempt to connect }
if (client.connect(clientName)) {
Serial.println("connected");
// Once connected, publish an announcement...
client.publish("outTopic", "hello world");
// ... and resubscribe
client.subscribe("inTopic"); void verifyFingerprint() {
} else { unsigned long Pause = 0;
Serial.print("failed, rc="); if(client.connected() || espClient.connected()) return; //Already connected
Serial.print(client.state());
Serial.println(" try again in 5 seconds"); Serial.print("\n\tChecking TLS @ ");
// Wait 5 seconds before retrying Serial.print(mqtt_server);
delay(5000); Serial.print("...");
ESP.restart();
} if (!espClient.connect(mqtt_server, mqtt_port)) {
} //Serial.println("\n\tConnection failed. Rebooting.");
} Serial.println("\n\tConnection failed.");
Serial.flush();
void datenSave(int wert){ //blink.detach();
File k = LittleFS.open("/status.txt", "w"); //blink.attach(0.05, flip);
if(!k){ //delay(5000);
Serial.println("file open failed"); endTime = millis();
} Pause = stoerung -((endTime - startTime) * 1000); // Pause ca. 15 Minuten
k.println(wert); Serial.print("\tIch gehe für "); Serial.print((Pause/1000/1000/60)+1); Serial.println( " Minuten schlafen.");
k.close(); ESP.deepSleep(Pause, WAKE_RF_DISABLED); // Pause
} delay(500);
}
int readDaten() espClient.stop();
{ delay(100);
int Error; }
File k = LittleFS.open("/status.txt", "r"); void pulse_pin(uint8_t pin)
if(!k){ {
Serial.println("file open failed"); digitalWrite(pin, LOW);
Error = -10; delay(1);
}else{ digitalWrite(pin, HIGH);
String data = k.readString(); }
Error = data.toInt();
k.close();
}
return Error;
}
int saveKorektur(float wert){
int Error = 0;
File k = LittleFS.open("/Korektur.txt", "w");
if(!k){
Serial.println("file open failed");
Error = -1;
}else{
k.println(String(wert,8));
k.close();
}
return Error;
}
float readKorectur(){
float Korektur;
File k = LittleFS.open("/Korektur.txt", "r");
if(!k){
Serial.println("file open failed");
Korektur = 1.00;
}else{
String data = k.readString();
Korektur = data.toFloat();
k.close();
}
return Korektur;
}
void verifyFingerprint() {
unsigned long Pause = 0;
if(client.connected() || espClient.connected()) return; //Already connected
Serial.print("\n\tChecking TLS @ ");
Serial.print(mqtt_server);
Serial.print("...");
if (!espClient.connect(mqtt_server, mqtt_port)) {
//Serial.println("\n\tConnection failed. Rebooting.");
Serial.println("\n\tConnection failed.");
Serial.flush();
//blink.detach();
//blink.attach(0.05, flip);
//delay(5000);
endTime = millis();
Pause = stoerung -((endTime - startTime) * 1000); // Pause ca. 15 Minuten
Serial.print("\tIch gehe für "); Serial.print((Pause/1000/1000/60)+1); Serial.println( " Minuten schlafen.");
ESP.deepSleep(Pause, WAKE_RF_DISABLED); // Pause
delay(500);
}
espClient.stop();
delay(100);
}
void pulse_pin(uint8_t pin)
{
digitalWrite(pin, LOW);
delay(1);
digitalWrite(pin, HIGH);
}

View File

@ -1,11 +1,11 @@
This directory is intended for PlatformIO Test Runner and project tests. This directory is intended for PlatformIO Test Runner and project tests.
Unit Testing is a software testing method by which individual units of Unit Testing is a software testing method by which individual units of
source code, sets of one or more MCU program modules together with associated source code, sets of one or more MCU program modules together with associated
control data, usage procedures, and operating procedures, are tested to control data, usage procedures, and operating procedures, are tested to
determine whether they are fit for use. Unit testing finds problems early determine whether they are fit for use. Unit testing finds problems early
in the development cycle. in the development cycle.
More information about PlatformIO Unit Testing: More information about PlatformIO Unit Testing:
- https://docs.platformio.org/en/latest/advanced/unit-testing/index.html - https://docs.platformio.org/en/latest/advanced/unit-testing/index.html

View File

@ -1,4 +0,0 @@
{
"folders": [],
"settings": {}
}