/*
* Blink
* Turns on an LED on for one second ,
* then off for one second , repeatedly .
*/
# include <Arduino.h>
# include <WiFi.h>
# include <WiFiMulti.h>
# include <Wire.h>
# include <SPI.h>
# include <GxEPD2_BW.h>
# include <Fonts/FreeMonoBold9pt7b.h>
# include <Fonts/FreeSans9pt7b.h>
# include <Fonts/FreeSansBold9pt7b.h>
# include <Fonts/Org_01.h>
# include "bitmaps/Bitmaps128x250.h"
# include <Adafruit_GFX.h>
# include <Adafruit_Sensor.h>
# include "Adafruit_BME280.h"
# include "Adafruit_BME680.h"
# include "Adafruit_VEML6075.h"
# include <BH1750.h>
# define ARDUINO_SAMD_VARIANT_COMPLIANCE
# include "SdsDustSensor.h"
# include "network/XD0OTA.h"
# include "network/XD0MQTT.h"
# include <ArduinoJson.h>
# include "SensorHistory.h"
# include "icons.h"
extern " C " {
uint8_t temprature_sens_read ( ) ;
}
static const char * TAG = " MAIN " ;
# define TIME_TO_SLEEP 60 // seconds
constexpr unsigned int dhcp_interval = 60 * 60 ;
WiFiMulti wifiMulti ;
GxEPD2_BW < GxEPD2_213_B72 , GxEPD2_213_B72 : : HEIGHT > display ( GxEPD2_213_B72 ( /*CS=SS*/ TFT_CS , /*DC=*/ TFT_DC , /*RST=*/ TFT_RST , /*BUSY=*/ - 1 ) ) ; // GDEH0213B72
static constexpr uint8_t y_offset = 6 ;
Adafruit_BME280 bme280 ; // I2C (also available: hardware SPI
Adafruit_BME680 bme680 ; // I2C (also available: hardware SPI
//HardwareSerial Serial2(2);
SdsDustSensor sds ( Serial2 ) ;
Adafruit_VEML6075 uv = Adafruit_VEML6075 ( ) ;
BH1750 lightMeter ;
constexpr unsigned int JSON_BUF_LEN = 512 ;
constexpr unsigned int JSON_CAPACITY = JSON_OBJECT_SIZE ( 16 ) + 0 * JSON_ARRAY_SIZE ( 2 ) + 120 ;
XD0MQTT mqtt ;
XD0OTA ota ( " esp32-weatherstation " ) ;
struct __attribute__ ( ( packed ) ) network_t {
uint32_t ip ;
uint32_t dns ;
uint32_t gateway ;
uint32_t subnet ;
char ssid [ 64 ] ;
char password [ 64 ] ;
int32_t channel ;
time_t last_dhcp ;
} ;
RTC_DATA_ATTR network_t network ;
struct __attribute__ ( ( packed ) ) sensor_readings_t {
float temperature = NAN ; // °C
float humidity = NAN ; // %H
float pressure = NAN ; // hPa
float pressure_raw = NAN ; // Pa
uint32_t voc = 0 ; // Ohm
float pm10 = NAN ; // µg/m³
float pm25 = NAN ; // µg/m³
float lux = NAN ; // lx
float uvi = NAN ;
float uva = NAN ;
float uvb = NAN ;
float temperature_max = NAN ; // °C
float temperature_min = NAN ; // °C
float voltage = NAN ; // V
int8_t rssi = 0 ; // dBm
time_t lastUpdate = 0 ;
} sensor_readings ;
sensor_readings_t sensors_a4cf1211c3e4 , sensors_246f28d1fa5c , sensors_246f28d1a080 , sensors_246f28d1eff4 ;
SensorHistory history_pressure ( 30 ) ;
RTC_DATA_ATTR time_t lastDisplayRefresh = 0 ;
struct __attribute__ ( ( packed ) ) sensors_active_t {
bool bme280 = false ;
bool bme680 = false ;
bool uv = false ;
bool light = false ;
bool sds = false ;
} ;
RTC_DATA_ATTR sensors_active_t sensors_active ;
float station_height = 0 ;
RTC_DATA_ATTR int bootCount = 0 ;
time_t getTimestamp ( ) {
struct timeval tv ;
gettimeofday ( & tv , NULL ) ;
return tv . tv_sec ;
}
void poweroffDevices ( ) {
display . powerOff ( ) ;
if ( sensors_active . bme680 ) {
bme680 . setGasHeater ( 0 , 0 ) ;
}
if ( sensors_active . bme280 ) {
bme280 . setSampling ( Adafruit_BME280 : : MODE_SLEEP ,
Adafruit_BME280 : : SAMPLING_X1 , // temperature
Adafruit_BME280 : : SAMPLING_X1 , // pressure
Adafruit_BME280 : : SAMPLING_X1 , // humidity
Adafruit_BME280 : : FILTER_OFF ) ;
}
if ( sensors_active . light ) {
static constexpr byte BH1750_I2CADDR = 0x23 ;
Wire . beginTransmission ( BH1750_I2CADDR ) ;
Wire . write ( BH1750_POWER_DOWN ) ;
byte ack = Wire . endTransmission ( ) ;
}
if ( sensors_active . uv ) {
uv . shutdown ( true ) ;
}
//if (sensors_active.sds) {
// sds.sleep(); // use custom working period instead
//}
}
void gotoSleep ( unsigned int sleep_time = TIME_TO_SLEEP ) {
mqtt . end ( ) ;
WiFi . disconnect ( ) ;
WiFi . mode ( WIFI_OFF ) ;
poweroffDevices ( ) ;
//rtc_gpio_isolate(GPIO_NUM_12);
esp_sleep_enable_timer_wakeup ( sleep_time * 1000000LL ) ;
esp_sleep_pd_config ( ESP_PD_DOMAIN_RTC_PERIPH , ESP_PD_OPTION_OFF ) ;
ESP_LOGI ( TAG , " going to to sleep for %d seconds " , sleep_time ) ;
Serial . flush ( ) ;
esp_deep_sleep_start ( ) ;
delay ( 1 ) ;
}
void wifiConnect ( ) {
WiFi . persistent ( false ) ;
WiFi . setHostname ( " esp32-weatherstation " ) ;
wifiMulti . addAP ( WIFI_SSID , WIFI_PASSWD ) ;
wifiMulti . addAP ( WIFI_SSID2 , WIFI_PASSWD2 ) ;
wifiMulti . addAP ( WIFI_SSID3 , WIFI_PASSWD3 ) ;
IPAddress ip = IPAddress ( network . ip ) ;
IPAddress dns = IPAddress ( network . dns ) ;
IPAddress subnet = IPAddress ( network . subnet ) ;
IPAddress gateway = IPAddress ( network . gateway ) ;
Serial . println ( " millis(): " + String ( millis ( ) ) ) ;
ESP_LOGD ( TAG , " previous dhcp: %lu s ago " , getTimestamp ( ) - network . last_dhcp ) ;
if ( ip ! = INADDR_NONE & & dns ! = INADDR_NONE & & gateway ! = INADDR_NONE & & subnet ! = INADDR_NONE
& & ( ( ip [ 0 ] = = 192 & & ip [ 1 ] = = 168 ) | | ( ip [ 0 ] = = 172 & & ip [ 1 ] = = 16 ) )
& & strlen ( network . ssid ) > 0 & & strlen ( network . password ) > 0
& & ( getTimestamp ( ) - network . last_dhcp < dhcp_interval )
) {
ESP_LOGD ( " WiFi " , " STATIC IP " ) ;
WiFi . config ( ip , gateway , subnet , dns ) ;
WiFi . begin ( network . ssid , network . password , network . channel ) ;
for ( int tries = 0 ; WiFi . status ( ) ! = WL_CONNECTED & & tries < 10 ; tries + + ) {
ESP_LOGD ( " WiFi " , " . " ) ;
delay ( 500 ) ;
}
} else {
ESP_LOGD ( " WiFi " , " DHCP " ) ;
for ( int tries = 0 ; wifiMulti . run ( ) ! = WL_CONNECTED & & tries < 20 ; tries + + ) {
ESP_LOGD ( " WiFi " , " . " ) ;
delay ( 500 ) ;
}
network . ip = ( uint32_t ) WiFi . localIP ( ) ;
network . dns = ( uint32_t ) WiFi . dnsIP ( ) ;
network . gateway = ( uint32_t ) WiFi . gatewayIP ( ) ;
network . subnet = ( uint32_t ) WiFi . subnetMask ( ) ;
strncpy ( network . ssid , WiFi . SSID ( ) . c_str ( ) , 64 ) ;
strncpy ( network . password , WiFi . psk ( ) . c_str ( ) , 64 ) ;
network . channel = WiFi . channel ( ) ;
network . last_dhcp = getTimestamp ( ) ;
}
Serial . println ( " millis(): " + String ( millis ( ) ) ) ;
if ( WiFi . status ( ) = = WL_CONNECTED ) {
ESP_LOGD ( " WiFi " , " connected " ) ;
//ESP_LOGD("WiFi", (WiFi.localIP().toString().c_str()));
} else {
ESP_LOGE ( " WiFi " , " could not connect to WiFi " ) ;
ESP_LOGE ( TAG , " restarting " ) ;
ESP . restart ( ) ;
}
}
bool obtain_time ( ) {
ESP_LOGI ( TAG , " syncing time " ) ;
configTzTime ( " CET-1CEST,M3.5.0/2,M10.5.0/3 " , " de.pool.ntp.org " ) ;
struct tm timeinfo ;
return getLocalTime ( & timeinfo , 5000 ) ;
}
void helloWorld ( )
{
const char HelloWorld [ ] = " IchbinsBens! " ;
//Serial.println("helloWorld");
display . setRotation ( 1 ) ;
display . setFont ( & FreeMonoBold9pt7b ) ;
display . setTextColor ( GxEPD_BLACK ) ;
int16_t tbx , tby ; uint16_t tbw , tbh ;
display . getTextBounds ( HelloWorld , 0 , 0 , & tbx , & tby , & tbw , & tbh ) ;
// center bounding box by transposition of origin:
uint16_t x = ( ( display . width ( ) - tbw ) / 2 ) - tbx ;
uint16_t y = ( ( display . height ( ) - tbh ) / 2 ) - tby ;
if ( display . epd2 . hasFastPartialUpdate ) {
display . setPartialWindow ( 0 , 0 , display . width ( ) , display . height ( ) ) ;
} else {
display . setFullWindow ( ) ;
}
display . firstPage ( ) ;
do
{
display . fillScreen ( GxEPD_WHITE ) ;
display . setCursor ( x , y ) ;
display . print ( HelloWorld ) ;
display . setCursor ( 5 , display . height ( ) - 5 ) ;
display . setFont ( & Org_01 ) ;
display . print ( FW_VERSION ) ;
}
while ( display . nextPage ( ) ) ;
//Serial.println("helloWorld done");
}
void displayIcoPartial ( const uint8_t bitmap [ ] , uint16_t x , uint16_t y , uint16_t w , uint16_t h ) {
display . setPartialWindow ( x , y , w , h ) ;
display . firstPage ( ) ; do {
display . drawInvertedBitmap ( x , y , bitmap , w , h , GxEPD_BLACK ) ;
} while ( display . nextPage ( ) ) ;
}
void getTime ( char * ptr , size_t maxsize , const char * format ) {
time_t now ;
struct tm timeinfo ;
time ( & now ) ; // update 'now' variable with current time
setenv ( " TZ " , " CET-1CEST,M3.5.0/2,M10.5.0/3 " , 1 ) ;
tzset ( ) ;
localtime_r ( & now , & timeinfo ) ;
strftime ( ptr , maxsize , format , & timeinfo ) ;
}
void getSensorMeasurements ( ) {
if ( sensors_active . bme280 ) {
bme280 . takeForcedMeasurement ( ) ;
sensor_readings . temperature = bme280 . readTemperature ( ) ;
sensor_readings . humidity = bme280 . readHumidity ( ) ;
sensor_readings . pressure_raw = bme280 . readPressure ( ) ;
ESP_LOGI ( TAG , " Temperature : %8.2f °C " , sensor_readings . temperature ) ;
ESP_LOGI ( TAG , " Pressure (Raw): %8.2f Pa " , sensor_readings . pressure_raw ) ;
ESP_LOGI ( TAG , " Humidity : %8.2f % " , sensor_readings . humidity ) ;
}
if ( sensors_active . bme680 ) {
bme680 . endReading ( ) ; // ToDo
if ( bme680 . performReading ( ) ) {
sensor_readings . temperature = bme680 . temperature ;
sensor_readings . humidity = bme680 . humidity ;
sensor_readings . pressure_raw = bme680 . pressure ;
sensor_readings . voc = bme680 . gas_resistance ;
ESP_LOGI ( TAG , " Temperature : %8.2f °C " , sensor_readings . temperature ) ;
ESP_LOGI ( TAG , " Pressure (Raw): %8.2f Pa " , sensor_readings . pressure_raw ) ;
ESP_LOGI ( TAG , " Humidity : %8.2f % " , sensor_readings . humidity ) ;
ESP_LOGI ( TAG , " VOC : %5lu kOhm " , sensor_readings . voc ) ;
} else {
ESP_LOGE ( TAG , " Failed to perform BME680 reading :( " ) ;
}
}
if ( sensor_readings . temperature > sensor_readings . temperature_max
| | isnan ( sensor_readings . temperature_max ) ) {
sensor_readings . temperature_max = sensor_readings . temperature ;
}
if ( sensor_readings . temperature < sensor_readings . temperature_min
| | isnan ( sensor_readings . temperature_min ) ) {
sensor_readings . temperature_min = sensor_readings . temperature ;
}
// https://de.wikipedia.org/wiki/Barometrische_H%C3%B6henformel#Reduktion_auf_Meeresh%C3%B6he
// https://carnotcycle.wordpress.com/2012/08/04/how-to-convert-relative-humidity-to-absolute-humidity/
float absolute_humidity = ( 6.112 * exp ( ( 17.67 * sensor_readings . temperature ) / ( sensor_readings . temperature + 243.5 ) ) * ( sensor_readings . humidity / 100 ) * 18.02 ) / ( ( 273.15 + sensor_readings . temperature ) * 1000 * 0.08314 ) ;
float pressure_compensation_factor = exp ( ( 9.80665 / ( 287.05 * ( sensor_readings . temperature + 273.15 + 0.12 * ( ( absolute_humidity * 461.5 * ( sensor_readings . temperature + 273.15 ) / 100 ) / 100 ) + 0.0065 * ( station_height / 2 ) ) ) ) * station_height ) ;
sensor_readings . pressure = ( sensor_readings . pressure_raw / 100.0F ) * pressure_compensation_factor ;
history_pressure . addValue ( sensor_readings . pressure ) ;
if ( sensors_active . uv ) {
sensor_readings . uvi = uv . readUVI ( ) ;
sensor_readings . uva = uv . readUVA ( ) ;
sensor_readings . uvb = uv . readUVB ( ) ;
ESP_LOGI ( TAG , " UVI : %8.2f " , sensor_readings . uvi ) ;
ESP_LOGI ( TAG , " UVA : %8.2f " , sensor_readings . uva ) ;
ESP_LOGI ( TAG , " UVB : %8.2f " , sensor_readings . uvb ) ;
}
if ( sensors_active . light ) {
sensor_readings . lux = lightMeter . readLightLevel ( ) ;
// auto-adjust sensitivity
if ( sensor_readings . lux < 0 ) {
ESP_LOGE ( TAG , " Error reading light level " ) ;
} else if ( sensor_readings . lux > 40000.0 ) {
if ( lightMeter . setMTreg ( 32 ) ) {
ESP_LOGD ( TAG , " Setting MTReg to low value for high light environment " ) ;
}
} else if ( sensor_readings . lux < = 10.0 ) {
if ( lightMeter . setMTreg ( 138 ) ) {
ESP_LOGD ( TAG , " Setting MTReg to high value for low light environment " ) ;
}
} else { // if (sensor_readings.lux > 10.0)
if ( lightMeter . setMTreg ( 69 ) ) {
ESP_LOGD ( TAG , " Setting MTReg to default value for normal light environment " ) ;
}
}
ESP_LOGI ( TAG , " Lux : %8.2f lx " , sensor_readings . lux ) ;
}
if ( sensors_active . sds ) {
PmResult pm = sds . queryPm ( ) ;
if ( pm . isOk ( ) ) {
sensor_readings . pm10 = pm . pm10 ;
sensor_readings . pm25 = pm . pm25 ;
ESP_LOGI ( TAG , " PM10 : %8.2f µg/m³ " , sensor_readings . pm10 ) ;
ESP_LOGI ( TAG , " PM2.5 : %8.2f µg/m³ " , sensor_readings . pm25 ) ;
}
}
int battery = analogRead ( _VBAT ) ;
sensor_readings . voltage = ( battery / 4096.0 ) * 2 * 3.42 ;
sensor_readings . rssi = WiFi . RSSI ( ) ;
ESP_LOGI ( TAG , " RSSI : %5d dBm " , sensor_readings . rssi ) ;
ESP_LOGI ( TAG , " Battery : %5d " , battery ) ;
ESP_LOGI ( TAG , " Heap : %5lu " , ESP . getFreeHeap ( ) ) ;
sensor_readings . lastUpdate = getTimestamp ( ) ;
}
void receiveMqtt ( const char * topic , const char * data , int data_len ) {
sensor_readings_t * sensor = NULL ;
ESP_LOGI ( TAG , " received MQTT message on subscribed topic %s " , topic ) ;
if ( strstr ( topic , " thomas/sensor/a4cf1211c3e4 " ) = = topic ) {
sensor = & sensors_a4cf1211c3e4 ;
} else if ( strstr ( topic , " thomas/sensor/246f28d1fa5c " ) = = topic ) {
sensor = & sensors_246f28d1fa5c ;
} else if ( strstr ( topic , " thomas/sensor/246f28d1a080 " ) = = topic ) {
sensor = & sensors_246f28d1a080 ;
} else if ( strstr ( topic , " thomas/sensor/246f28d1eff4 " ) = = topic ) {
sensor = & sensors_246f28d1eff4 ;
}
char * topic_last = strrchr ( topic , ' / ' ) ;
if ( topic_last & & sensor ) {
if ( strcmp ( " /json " , topic_last ) = = 0 ) {
StaticJsonDocument < JSON_CAPACITY + 120 > jsonDoc ;
DeserializationError err = deserializeJson ( jsonDoc , data , data_len ) ;
if ( err ) {
ESP_LOGW ( TAG , " Error parsing JSON, code: %s " , err . c_str ( ) ) ;
} else {
// got json
if ( jsonDoc . containsKey ( " temperature " ) ) sensor - > temperature = jsonDoc [ " temperature " ] . as < float > ( ) ;
if ( jsonDoc . containsKey ( " humidity " ) ) sensor - > humidity = jsonDoc [ " humidity " ] . as < float > ( ) ;
if ( jsonDoc . containsKey ( " pressure " ) ) sensor - > pressure = jsonDoc [ " pressure " ] . as < float > ( ) ;
if ( jsonDoc . containsKey ( " voc " ) ) sensor - > voc = jsonDoc [ " voc " ] . as < uint32_t > ( ) ;
if ( jsonDoc . containsKey ( " lux " ) ) sensor - > lux = jsonDoc [ " lux " ] . as < float > ( ) ;
if ( jsonDoc . containsKey ( " uvi " ) ) sensor - > uvi = jsonDoc [ " uvi " ] . as < float > ( ) ;
if ( jsonDoc . containsKey ( " uva " ) ) sensor - > uva = jsonDoc [ " uva " ] . as < float > ( ) ;
if ( jsonDoc . containsKey ( " uvb " ) ) sensor - > uvb = jsonDoc [ " uvb " ] . as < float > ( ) ;
if ( jsonDoc . containsKey ( " pm10 " ) ) sensor - > pm10 = jsonDoc [ " pm10 " ] . as < float > ( ) ;
if ( jsonDoc . containsKey ( " pm2.5 " ) ) sensor - > pm25 = jsonDoc [ " pm2.5 " ] . as < float > ( ) ;
if ( jsonDoc . containsKey ( " voltage " ) ) sensor - > voltage = jsonDoc [ " voltage " ] . as < float > ( ) ;
if ( jsonDoc . containsKey ( " rssi " ) ) sensor - > rssi = jsonDoc [ " rssi " ] . as < int8_t > ( ) ;
if ( jsonDoc . containsKey ( " timestamp " ) ) sensor - > lastUpdate = jsonDoc [ " timestamp " ] . as < time_t > ( ) ;
ESP_LOGI ( TAG , " got new values from %s, timestamp: %lu " , topic , sensor - > lastUpdate ) ;
ESP_LOGI ( TAG , " %lu seconds ago " , topic , getTimestamp ( ) - sensor - > lastUpdate ) ;
}
} else if ( strcmp ( " /temperature " , topic_last ) = = 0 ) {
sensor - > temperature = atof ( data ) ;
sensor - > lastUpdate = getTimestamp ( ) ;
} else if ( strcmp ( " /humidity " , topic_last ) = = 0 ) {
sensor - > humidity = atof ( data ) ;
} else if ( strcmp ( " /pressure " , topic_last ) = = 0 ) {
sensor - > pressure = atof ( data ) ;
} else if ( strcmp ( " /pm10 " , topic_last ) = = 0 ) {
sensor - > pm10 = atof ( data ) ;
} else if ( strcmp ( " /pm25 " , topic_last ) = = 0 ) {
sensor - > pm25 = atof ( data ) ;
} else if ( strcmp ( " /lux " , topic_last ) = = 0 ) {
sensor - > lux = atof ( data ) ;
} else if ( strcmp ( " /uvi " , topic_last ) = = 0 ) {
sensor - > uvi = atof ( data ) ;
} else if ( strcmp ( " /uva " , topic_last ) = = 0 ) {
sensor - > uva = atof ( data ) ;
} else if ( strcmp ( " /uvb " , topic_last ) = = 0 ) {
sensor - > uvb = atof ( data ) ;
} else if ( strcmp ( " /voc " , topic_last ) = = 0 ) {
sensor - > voc = atof ( data ) ;
}
}
}
void displayValues ( ) {
display . setRotation ( 1 ) ;
display . setFont ( NULL ) ;
display . setTextColor ( GxEPD_BLACK ) ;
display . setTextSize ( 1 ) ;
display . setTextWrap ( false ) ;
char timeStr [ 40 ] ;
getTime ( timeStr , sizeof ( timeStr ) , " %d. %b %Y %H:%M:%S " ) ;
ESP_LOGD ( TAG , " displayValues() " ) ;
if ( display . epd2 . hasFastPartialUpdate ) {
display . setPartialWindow ( 0 , 0 , display . width ( ) , display . height ( ) ) ;
} else {
display . setFullWindow ( ) ;
}
display . firstPage ( ) ;
do
{
display . fillScreen ( GxEPD_WHITE ) ;
// Title
display . setCursor ( 30 , y_offset + 0 ) ;
display . println ( timeStr ) ;
display . drawLine ( 0 , y_offset + 10 , display . width ( ) , y_offset + 10 , GxEPD_BLACK ) ;
// Temp
display . drawRect ( 0 , y_offset + 10 , 64 , 50 , GxEPD_BLACK ) ;
display . setFont ( NULL ) ;
display . setCursor ( 5 , y_offset + 15 ) ;
display . printf ( " max: %.1f " , sensor_readings . temperature_max ) ;
display . setFont ( & FreeSansBold9pt7b ) ;
display . setCursor ( 5 , y_offset + 40 ) ;
display . printf ( " %.1f " , sensor_readings . temperature ) ;
display . setFont ( NULL ) ;
display . print ( " \xf7 \x43 " ) ;
display . setCursor ( 5 , y_offset + 45 ) ;
display . printf ( " min: %.1f " , sensor_readings . temperature_min ) ;
// Humidity
display . drawRect ( 63 , y_offset + 10 , 58 , 50 , GxEPD_BLACK ) ;
display . setFont ( NULL ) ;
display . setCursor ( 68 , y_offset + 15 ) ;
display . print ( " Humidity " ) ;
display . setFont ( & FreeSansBold9pt7b ) ;
display . setCursor ( 68 , y_offset + 40 ) ;
display . printf ( " %.1f " , sensor_readings . humidity ) ;
display . setFont ( NULL ) ;
display . print ( " \ % " ) ;
display . setCursor ( 68 , y_offset + 45 ) ;
if ( sensor_readings . humidity < 30 ) {
display . print ( " low " ) ;
} else if ( sensor_readings . humidity < 60 ) {
display . print ( " comfort " ) ;
} else {
display . print ( " high " ) ;
}
// Pressure
display . drawRect ( 120 , y_offset + 10 , 66 , 50 , GxEPD_BLACK ) ;
display . setFont ( NULL ) ;
display . setCursor ( 125 , y_offset + 15 ) ;
display . print ( " Pressure " ) ;
display . setFont ( & FreeSansBold9pt7b ) ;
display . setCursor ( 125 , y_offset + 40 ) ;
display . printf ( " %.1f " , sensor_readings . pressure ) ;
display . setFont ( NULL ) ;
//display.print(" hPa");
float pressure_diff = history_pressure . getElement ( 0 ) - history_pressure . getFirst ( ) ;
display . setCursor ( 125 , y_offset + 45 ) ;
if ( isnan ( pressure_diff ) | | history_pressure . getCount ( ) < history_pressure . getSize ( ) ) {
} else if ( pressure_diff > - 20 & & pressure_diff < - 0.6 ) {
display . print ( " Trend: \x19 \x19 " ) ;
} else if ( pressure_diff < - 0.1 ) {
display . print ( " Trend: \x19 " ) ;
} else if ( pressure_diff < 0.1 ) {
display . print ( " Trend: \x1a " ) ;
} else if ( pressure_diff < 0.6 ) {
display . print ( " Trend: \x18 " ) ;
} else if ( pressure_diff < 20 ) {
display . print ( " Trend: \x18 \x18 " ) ;
} else {
display . print ( " ? " ) ;
}
// Other
display . drawRect ( 185 , y_offset + 10 , 250 - 186 + 1 , 122 - 10 , GxEPD_BLACK ) ;
display . setFont ( NULL ) ;
// VOC
display . setCursor ( 190 , y_offset + 15 ) ;
display . println ( " -- VOC -- " ) ;
display . setCursor ( 190 , y_offset + 25 ) ;
display . printf ( " %.1f k \xe9 " , sensor_readings . voc / 1000.0F ) ;
// PM
float pm10 , pm25 ;
if ( sensors_active . sds ) {
pm10 = sensor_readings . pm10 ;
pm25 = sensor_readings . pm25 ;
} else if ( ! isnan ( sensors_a4cf1211c3e4 . pm10 ) | | ! isnan ( sensors_a4cf1211c3e4 . pm25 ) ) {
pm10 = sensors_a4cf1211c3e4 . pm10 ;
pm25 = sensors_a4cf1211c3e4 . pm25 ;
} else if ( ! isnan ( sensors_246f28d1fa5c . pm10 ) | | ! isnan ( sensors_246f28d1fa5c . pm25 ) ) {
pm10 = sensors_246f28d1fa5c . pm10 ;
pm25 = sensors_246f28d1fa5c . pm25 ;
} else if ( ! isnan ( sensors_246f28d1a080 . pm10 ) | | ! isnan ( sensors_246f28d1a080 . pm25 ) ) {
pm10 = sensors_246f28d1a080 . pm10 ;
pm25 = sensors_246f28d1a080 . pm25 ;
} else {
pm10 = NAN ;
pm25 = NAN ;
}
display . setCursor ( 190 , y_offset + 37 ) ;
display . println ( " -- PM -- " ) ;
display . setCursor ( 190 , y_offset + 47 ) ;
display . printf ( " %.1f " , pm10 ) ;
display . setCursor ( 220 , y_offset + 47 ) ;
display . printf ( " %.1f " , pm25 ) ;
// Lux
float lux ;
if ( sensors_active . light ) {
lux = sensor_readings . lux ;
} else if ( ! isnan ( sensors_a4cf1211c3e4 . lux ) ) {
lux = sensors_a4cf1211c3e4 . lux ;
} else if ( ! isnan ( sensors_246f28d1fa5c . lux ) ) {
lux = sensors_246f28d1fa5c . lux ;
} else if ( ! isnan ( sensors_246f28d1a080 . lux ) ) {
lux = sensors_246f28d1a080 . lux ;
} else {
lux = NAN ;
}
display . setCursor ( 190 , y_offset + 59 ) ;
display . println ( " -- Lux -- " ) ;
display . setCursor ( 190 , y_offset + 69 ) ;
display . printf ( " %.1f lx " , lux ) ;
// UV
float uvi , uva , uvb ;
if ( sensors_active . uv ) {
uvi = sensor_readings . uvi ;
uva = sensor_readings . uva ;
uvb = sensor_readings . uvb ;
} else if ( ! isnan ( sensors_a4cf1211c3e4 . uvi ) | | ! isnan ( sensors_a4cf1211c3e4 . uva ) | | ! isnan ( sensors_a4cf1211c3e4 . uvb ) ) {
uvi = sensors_a4cf1211c3e4 . uvi ;
uva = sensors_a4cf1211c3e4 . uva ;
uvb = sensors_a4cf1211c3e4 . uvb ;
} else if ( ! isnan ( sensors_246f28d1fa5c . uvi ) | | ! isnan ( sensors_246f28d1fa5c . uva ) | | ! isnan ( sensors_246f28d1fa5c . uvb ) ) {
uvi = sensors_246f28d1fa5c . uvi ;
uva = sensors_246f28d1fa5c . uva ;
uvb = sensors_246f28d1fa5c . uvb ;
} else if ( ! isnan ( sensors_246f28d1a080 . uvi ) | | ! isnan ( sensors_246f28d1a080 . uva ) | | ! isnan ( sensors_246f28d1a080 . uvb ) ) {
uvi = sensors_246f28d1a080 . uvi ;
uva = sensors_246f28d1a080 . uva ;
uvb = sensors_246f28d1a080 . uvb ;
} else {
uvi = NAN ;
uva = NAN ;
uvb = NAN ;
}
display . setCursor ( 190 , y_offset + 80 ) ;
display . println ( " UV(I/A/B): " ) ;
display . setCursor ( 190 , y_offset + 90 ) ;
display . printf ( " %.1f " , uvi ) ;
display . setCursor ( 190 , y_offset + 100 ) ;
display . printf ( " %.1f " , uva ) ;
display . setCursor ( 190 , y_offset + 110 ) ;
display . printf ( " %.1f " , uvb ) ;
// other nodes
display . setFont ( NULL ) ;
display . setCursor ( 0 , y_offset + 70 ) ;
if ( ! ota . getMAC ( ) . equals ( " 246f28d1fa5c " ) & & getTimestamp ( ) - sensors_246f28d1fa5c . lastUpdate < 15 * 60 ) {
display . printf ( " 246f28d1fa5c: %4.1f %4.1f %6.1f \n " , sensors_246f28d1fa5c . temperature , sensors_246f28d1fa5c . humidity , sensors_246f28d1fa5c . pressure ) ;
}
if ( ! ota . getMAC ( ) . equals ( " a4cf1211c3e4 " ) & & getTimestamp ( ) - sensors_a4cf1211c3e4 . lastUpdate < 15 * 60 ) {
display . printf ( " a4cf1211c3e4: %4.1f %4.1f %6.1f \n " , sensors_a4cf1211c3e4 . temperature , sensors_a4cf1211c3e4 . humidity , sensors_a4cf1211c3e4 . pressure ) ;
}
if ( ! ota . getMAC ( ) . equals ( " 246f28d1a080 " ) & & getTimestamp ( ) - sensors_246f28d1a080 . lastUpdate < 15 * 60 ) {
display . printf ( " 246f28d1a080: %4.1f %4.1f %6.1f \n " , sensors_246f28d1a080 . temperature , sensors_246f28d1a080 . humidity , sensors_246f28d1a080 . pressure ) ;
}
if ( ! ota . getMAC ( ) . equals ( " 246f28d1eff4 " ) & & getTimestamp ( ) - sensors_246f28d1eff4 . lastUpdate < 15 * 60 ) {
display . printf ( " 246f28d1eff4: %4.1f %4.1f %6.1f \n " , sensors_246f28d1eff4 . temperature , sensors_246f28d1eff4 . humidity , sensors_246f28d1eff4 . pressure ) ;
}
}
while ( display . nextPage ( ) ) ;
display . powerOff ( ) ;
}
void sendValues ( ) {
for ( int tries = 0 ; mqtt . isConnected ( ) = = false & & tries < 10 ; tries + + ) {
ESP_LOGD ( TAG , " waiting for mqtt connection " ) ;
delay ( 300 ) ;
}
/* send values MQTT JSON */
char buf [ JSON_BUF_LEN ] ;
StaticJsonDocument < JSON_CAPACITY > jsonDoc ;
if ( sensors_active . bme280 | | sensors_active . bme680 ) {
jsonDoc [ " temperature " ] = sensor_readings . temperature ;
jsonDoc [ " humidity " ] = sensor_readings . humidity ;
jsonDoc [ " pressure " ] = sensor_readings . pressure ;
}
if ( sensors_active . bme680 ) {
jsonDoc [ " voc " ] = sensor_readings . voc ;
}
if ( sensors_active . light ) {
jsonDoc [ " lux " ] = sensor_readings . lux ;
}
if ( sensors_active . uv ) {
jsonDoc [ " uvi " ] = sensor_readings . uvi ;
jsonDoc [ " uva " ] = sensor_readings . uva ;
jsonDoc [ " uvb " ] = sensor_readings . uvb ;
}
if ( sensors_active . sds ) {
jsonDoc [ " pm10 " ] = sensor_readings . pm10 ;
jsonDoc [ " pm2.5 " ] = sensor_readings . pm25 ;
}
jsonDoc [ " voltage " ] = sensor_readings . voltage ;
jsonDoc [ " rssi " ] = sensor_readings . rssi ;
jsonDoc [ " timestamp " ] = sensor_readings . lastUpdate ;
serializeJson ( jsonDoc , buf , JSON_BUF_LEN ) ;
String topic_json = String ( " thomas/sensor/ " ) + ota . getMAC ( ) + String ( " /json " ) ;
mqtt . publish ( topic_json . c_str ( ) , buf , strlen ( buf ) , 1 , 1 ) ;
delay ( 10 ) ;
}
/**
* \ brief Setup function
*
* is run once on startup
*/
void setup ( )
{
Serial . begin ( 115200 ) ;
Serial2 . begin ( 9600 , SERIAL_8N1 , /*rx*/ 15 , /*tx*/ 2 ) ; // IMPORTANT: don't run with default pins 16, 17 as they are connected to PSRAM on boards that ship with it
esp_sleep_wakeup_cause_t wakeup_reason = esp_sleep_get_wakeup_cause ( ) ;
+ + bootCount ;
ESP_LOGI ( TAG , " Boot number: %d " , bootCount ) ;
Serial . println ( " millis(): " + String ( millis ( ) ) ) ;
ESP_LOGD ( TAG , " setup hardware and sensors " ) ;
// initialize LED digital pin as an output.
pinMode ( LED_BUILTIN , OUTPUT ) ;
digitalWrite ( LED_BUILTIN , HIGH ) ;
pinMode ( _VBAT , INPUT ) ;
analogReadResolution ( 12 ) ;
analogSetAttenuation ( ADC_11db ) ;
adcAttachPin ( _VBAT ) ;
adcStart ( _VBAT ) ;
Serial . println ( " millis(): " + String ( millis ( ) ) ) ;
# define BME_SDA 21
# define BME_SCL 22
Wire . begin ( BME_SDA , BME_SCL ) ;
if ( bme280 . begin ( ) ) {
sensors_active . bme280 = true ;
} else {
ESP_LOGE ( TAG , " Could not find a valid BME280 sensor, check wiring! " ) ;
}
Serial . println ( " millis(): " + String ( millis ( ) ) ) ;
if ( bme680 . begin ( ) ) {
sensors_active . bme680 = true ;
// Set up oversampling and filter initialization
bme680 . setTemperatureOversampling ( BME680_OS_8X ) ;
bme680 . setHumidityOversampling ( BME680_OS_2X ) ;
bme680 . setPressureOversampling ( BME680_OS_4X ) ;
bme680 . setIIRFilterSize ( BME680_FILTER_SIZE_3 ) ;
bme680 . setGasHeater ( 320 , 150 ) ; // 320*C for 150 ms
bme680 . beginReading ( ) ;
} else {
ESP_LOGE ( TAG , " Could not find a valid BME680 sensor, check wiring! " ) ;
}
Serial . println ( " millis(): " + String ( millis ( ) ) ) ;
if ( uv . begin ( ) ) {
sensors_active . uv = true ;
uv . setIntegrationTime ( VEML6075_100MS ) ; // Set the integration constant
uv . setHighDynamic ( true ) ; // Set the high dynamic mode
uv . setForcedMode ( false ) ;
// Set the calibration coefficients
uv . setCoefficients ( 2.22 , 1.33 , // UVA_A and UVA_B coefficients
2.95 , 1.74 , // UVB_C and UVB_D coefficients
0.001461 , 0.002591 ) ; // UVA and UVB responses
} else {
ESP_LOGW ( TAG , " Failed to communicate with VEML6075 sensor, check wiring? " ) ;
}
Serial . println ( " millis(): " + String ( millis ( ) ) ) ;
if ( lightMeter . begin ( ) ) {
sensors_active . light = true ;
lightMeter . setMTreg ( ( byte ) BH1750_DEFAULT_MTREG ) ;
} else {
ESP_LOGW ( TAG , " Failed to communicate with BH1750 sensor, check wiring? " ) ;
}
Serial . println ( " millis(): " + String ( millis ( ) ) ) ;
//sds.begin(); // don't call begin, only messes with Serial
Serial . println ( " millis(): " + String ( millis ( ) ) ) ;
if ( wakeup_reason = = ESP_SLEEP_WAKEUP_UNDEFINED | | bootCount = = 1 ) {
FirmwareVersionResult sds_fw = sds . queryFirmwareVersion ( ) ;
if ( sds_fw . isOk ( ) ) {
sensors_active . sds = true ;
sds . setQueryReportingMode ( ) ; // ensures sensor is in 'query' reporting mode
sds . setCustomWorkingPeriod ( 5 ) ; // sensor sends data every 3 minutes
} else {
ESP_LOGW ( TAG , " Failed to communicate with SDS011 sensor, check wiring? " ) ;
}
}
Serial . println ( " millis(): " + String ( millis ( ) ) ) ;
// initialize e-paper display
SPI . begin ( 18 , 19 , 23 , TFT_CS ) ; // MISO is not connected to TFT_MISO!
display . init ( 0 , false , false ) ;
display . setRotation ( 1 ) ;
Serial . println ( " millis(): " + String ( millis ( ) ) ) ;
if ( wakeup_reason = = ESP_SLEEP_WAKEUP_UNDEFINED | | bootCount = = 1 ) {
// wakeup not caused by deep sleep
display . clearScreen ( ) ;
display . refresh ( ) ;
lastDisplayRefresh = getTimestamp ( ) ;
helloWorld ( ) ;
display . powerOff ( ) ;
} else {
// wakeup by deep sleep
// displayValues();
}
ESP_LOGD ( TAG , " connecting to WiFi " ) ;
Serial . println ( " millis(): " + String ( millis ( ) ) ) ;
wifiConnect ( ) ;
WiFi . waitForConnectResult ( ) ;
displayIcoPartial ( ico_wifi16 , display . width ( ) - 20 , y_offset + 0 , ico_wifi16_width , ico_wifi16_height ) ;
if ( wakeup_reason = = ESP_SLEEP_WAKEUP_UNDEFINED | | bootCount = = 1 ) {
// wakeup not caused by deep sleep
obtain_time ( ) ;
ESP_LOGD ( TAG , " trying to fetch over-the-air update " ) ;
if ( WiFi . status ( ) = = WL_CONNECTED ) {
ota . update ( ) ;
}
}
WiFi . setSleep ( true ) ;
ESP_LOGD ( TAG , " connecting to MQTT " ) ;
mqtt . begin ( ) ;
if ( ! ota . getMAC ( ) . equals ( " a4cf1211c3e4 " ) ) mqtt . subscribe ( " thomas/sensor/a4cf1211c3e4/json " , receiveMqtt ) ;
if ( ! ota . getMAC ( ) . equals ( " 246f28d1fa5c " ) ) mqtt . subscribe ( " thomas/sensor/246f28d1fa5c/json " , receiveMqtt ) ;
if ( ! ota . getMAC ( ) . equals ( " 246f28d1a080 " ) ) mqtt . subscribe ( " thomas/sensor/246f28d1a080/json " , receiveMqtt ) ;
if ( ! ota . getMAC ( ) . equals ( " 246f28d1eff4 " ) ) mqtt . subscribe ( " thomas/sensor/246f28d1eff4/json " , receiveMqtt ) ;
if ( WiFi . SSID ( ) = = " LNet " ) {
station_height = 135 ;
} else if ( WiFi . SSID ( ) = = " Galaktisches Imperium " ) {
station_height = 30 ;
} else if ( WiFi . SSID ( ) = = " nether.net " ) {
station_height = 111 ;
}
ESP_LOGD ( TAG , " setup done " ) ;
}
/**
* \ brief Arduino main loop
*/
void loop ( )
{
/* if(wifiMulti.run() != WL_CONNECTED) {
Serial . println ( " WiFi not connected! " ) ;
delay ( 1000 ) ;
} */
/* Do a full refresh every hour */
if ( getTimestamp ( ) - lastDisplayRefresh > = 60 * 60 ) {
lastDisplayRefresh = getTimestamp ( ) ;
display . clearScreen ( ) ;
display . refresh ( ) ;
}
getSensorMeasurements ( ) ;
sendValues ( ) ;
delay ( 1 ) ;
displayValues ( ) ;
int runtime = millis ( ) / 1000 ;
if ( runtime < 0 | | runtime > = TIME_TO_SLEEP ) runtime = 0 ;
gotoSleep ( TIME_TO_SLEEP - runtime ) ;
delay ( 2000 ) ;
}