Merge pull request #569 from cyberman54/development

Development
This commit is contained in:
Verkehrsrot 2020-03-20 12:24:39 +01:00 committed by GitHub
commit 4c5721be53
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
30 changed files with 565 additions and 238 deletions

View File

@ -58,7 +58,7 @@ Depending on board hardware following features are supported:
- Silicon unique ID - Silicon unique ID
- Battery voltage monitoring - Battery voltage monitoring
- GPS (Generic serial NMEA, or Quectel L76 I2C) - GPS (Generic serial NMEA, or Quectel L76 I2C)
- Environmental sensor (Bosch BMP180/BME280/BME680 I2C) - Environmental sensors (Bosch BMP180/BME280/BME680 I2C; SDS011 serial)
- Real Time Clock (Maxim DS3231 I2C) - Real Time Clock (Maxim DS3231 I2C)
- IF482 (serial) and DCF77 (gpio) time telegram generator - IF482 (serial) and DCF77 (gpio) time telegram generator
- Switch external power / battery - Switch external power / battery
@ -82,25 +82,28 @@ By default bluetooth sniffing is disabled (#define *BLECOUNTER* 0 in paxcounter.
# Preparing # Preparing
Before compiling the code, Compile time configuration is spread across several files. Before compiling the code, edit or create the following files:
- **edit platformio.ini** and select desired hardware target in section boards. To add a new board, create an appropriate hardware abstraction layer file in hal subdirectory, and add a pointer to this file in sections boards. ## platformio.ini
Edit `platformio.ini` and select desired hardware target in section boards. To add a new board, create an appropriate hardware abstraction layer file in hal subdirectory, and add a pointer to this file in sections boards.
- **edit src/paxcounter.conf** and tailor settings in this file according to your needs and use case. Please take care of the duty cycle regulations of the LoRaWAN network you're going to use. ## src/paxcounter.conf
Edit `src/paxcounter.conf` and tailor settings in this file according to your needs and use case. Please take care of the duty cycle regulations of the LoRaWAN network you're going to use.
- **edit src/lmic_config.h** and tailor settings in this file according to your country and device hardware. Please take care of national regulations when selecting the frequency band for LoRaWAN. If your device has a **real time clock** it can be updated bei either LoRaWAN network or GPS time, according to settings *TIME_SYNC_INTERVAL* and *TIME_SYNC_LORAWAN* in `paxcounter.conf`.
- **create file loraconf.h in your local /src directory** using the template [loraconf.sample.h](https://github.com/cyberman54/ESP32-Paxcounter/blob/master/src/loraconf.sample.h) and populate it with your personal APPEUI und APPKEY for the LoRaWAN network. If you're using popular <A HREF="https://thethingsnetwork.org">TheThingsNetwork</A> you can copy&paste the keys from TTN console or output of ttnctl. ## src/lmic_config.h
Edit `src/lmic_config.h` and tailor settings in this file according to your country and device hardware. Please take care of national regulations when selecting the frequency band for LoRaWAN.
- **create file ota.conf in your local /src directory** using the template [ota.sample.conf](https://github.com/cyberman54/ESP32-Paxcounter/blob/master/src/ota.sample.conf) and enter your WIFI network&key. These settings are used for downloading updates. If you want to push own OTA updates you need a <A HREF="https://bintray.com/JFrog">Bintray account</A>. Enter your Bintray user account data in ota.conf. If you don't need wireless firmware updates just rename ota.sample.conf to ota.conf. ## src/loraconf.h
Create file `src/loraconf.h` using the template [src/loraconf.sample.h](https://github.com/cyberman54/ESP32-Paxcounter/blob/master/src/loraconf.sample.h) and modify it, to use your personal values.
To join the network and activate your paxcounter, you have to configure either the preferred OTAA method or the ABP method. You should use OTAA, whenever possible. To understand the differences of the two methods, [this article](https://www.thethingsnetwork.org/docs/devices/registration.html) may be useful.
To join the network only method OTAA is supported, not ABP. The DEVEUI for OTAA will be derived from the device's MAC adress during device startup and is shown on the device's display (if it has one). It is also printed on the serial console for copying it, if you set *verbose 1* in paxcounter.conf and *debug_level 3* in platformio.ini. To configure OTAA, leave `#define LORA_ABP` deactivated (commented). To use ABP, activate (uncomment) `#define LORA_ABP` in the file `src/loraconf.h`.
The file `src/loraconf.h.sample` contains more information about the values to provide.
If your device has a fixed DEVEUI enter this in your local loraconf.h file. During compile time this DEVEUI will be grabbed from loraconf.h and inserted in the code. ## src/ota.conf
Create file `src/ota.conf` using the template [src/ota.sample.conf](https://github.com/cyberman54/ESP32-Paxcounter/blob/master/src/ota.sample.conf) and enter your WIFI network&key. These settings are used for downloading updates. If you want to push own OTA updates you need a <A HREF="https://bintray.com/JFrog">Bintray account</A>. Enter your Bintray user account data in ota.conf. If you don't need wireless firmware updates just rename ota.sample.conf to ota.conf.
If your device has silicon **Unique ID** which is stored in serial EEPROM Microchip 24AA02E64 you don't need to change anything. The Unique ID will be read during startup and DEVEUI will be generated from it, overriding settings in loraconf.h.
If your device has a **real time clock** it can be updated bei either LoRaWAN network or GPS time, according to settings *TIME_SYNC_INTERVAL* and *TIME_SYNC_LORAWAN* in paxcounter.conf.
# Building # Building
@ -167,7 +170,7 @@ by pressing the button of the device.
# Sensors and Peripherals # Sensors and Peripherals
You can add up to 3 user defined sensors. Insert sensor's payload scheme in [*sensor.cpp*](src/sensor.cpp). Bosch BMP180 / BME280 / BME680 environment sensors are supported. Enable flag *lib_deps_sensors* for your board in [*platformio.ini*](src/platformio.ini) and configure BME in board's hal file before build. If you need Bosch's proprietary BSEC libraray (e.g. to get indoor air quality value from BME680) further enable *build_flags_sensors*, which comes on the price of reduced RAM and increased build size. RTC DS3231, generic serial NMEA GPS, I2C LoPy GPS are supported, and to be configured in board's hal file. See [*generic.h*](src/hal/generic.h) for all options and for proper configuration of BME280/BME680. You can add up to 3 user defined sensors. Insert sensor's payload scheme in [*sensor.cpp*](src/sensor.cpp). Bosch BMP180 / BME280 / BME680 environment sensors are supported. Enable flag *lib_deps_sensors* for your board in [*platformio.ini*](src/platformio.ini) and configure BME in board's hal file before build. If you need Bosch's proprietary BSEC libraray (e.g. to get indoor air quality value from BME680) further enable *build_flags_sensors*, which comes on the price of reduced RAM and increased build size. Furthermore, SDS011, RTC DS3231, generic serial NMEA GPS, I2C LoPy GPS are supported, and to be configured in board's hal file. See [*generic.h*](src/hal/generic.h) for all options and for proper configuration of BME280/BME680.
Output of user sensor data can be switched by user remote control command 0x14 sent to Port 2. Output of user sensor data can be switched by user remote control command 0x14 sent to Port 2.
@ -548,4 +551,4 @@ Thanks to
- [terrillmoore](https://github.com/mcci-catena) for maintaining the LMIC for arduino LoRaWAN stack - [terrillmoore](https://github.com/mcci-catena) for maintaining the LMIC for arduino LoRaWAN stack
- [sbamueller](https://github.com/sbamueller) for writing the tutorial in Make Magazine - [sbamueller](https://github.com/sbamueller) for writing the tutorial in Make Magazine
- [Stefan](https://github.com/nerdyscout) for paxcounter opensensebox integration - [Stefan](https://github.com/nerdyscout) for paxcounter opensensebox integration
- [August Quint](https://github.com/AugustQu) for adding SD card data logger support - [August Quint](https://github.com/AugustQu) for adding SD card data logger and SDS011 support

View File

@ -18,6 +18,15 @@
#include "display.h" #include "display.h"
#endif #endif
#if (HAS_SDS011)
#include "sds011read.h"
#endif
#if (HAS_SDCARD)
#include "sdcard.h"
#endif
extern Ticker housekeeper; extern Ticker housekeeper;
void housekeeping(void); void housekeeping(void);

View File

@ -3,15 +3,41 @@
#include "cyclic.h" #include "cyclic.h"
#include "qrcode.h" #include "qrcode.h"
#define DISPLAY_PAGES (7) // number of paxcounter display pages
// settings for oled display library
#define USE_BACKBUFFER 1
#define MY_OLED OLED_128x64
#ifdef MY_OLED_ADDR
#define OLED_ADDR MY_OLED_ADDR
#else
#define OLED_ADDR -1
#endif
#define OLED_INVERT 0
#define USE_HW_I2C 1
#ifndef DISPLAY_FLIP
#define DISPLAY_FLIP 0
#endif
// settings for qr code generator
#define QR_VERSION 3 // 29 x 29px
#define QR_SCALEFACTOR 2 // 29 -> 58x < 64px
// settings for curve plotter
#define DISPLAY_WIDTH 128 // Width in pixels of OLED-display, must be 32X
#define DISPLAY_HEIGHT 64 // Height in pixels of OLED-display, must be 64X
extern uint8_t DisplayIsOn, displaybuf[]; extern uint8_t DisplayIsOn, displaybuf[];
void setup_display(int contrast = 0);
void refreshTheDisplay(bool nextPage = false); void refreshTheDisplay(bool nextPage = false);
void init_display(bool verbose = false); void init_display(bool verbose = false);
void shutdown_display(void); void shutdown_display(void);
void draw_page(time_t t, bool nextpage); void draw_page(time_t t, bool nextpage);
void dp_printf(uint16_t x, uint16_t y, uint8_t font, uint8_t inv, void dp_printf(uint16_t x, uint16_t y, uint8_t font, uint8_t inv,
const char *format, ...); const char *format, ...);
void dp_dump(uint8_t *pBuffer);
void dp_printqr(uint16_t offset_x, uint16_t offset_y, const char *Message); void dp_printqr(uint16_t offset_x, uint16_t offset_y, const char *Message);
void oledfillRect(uint16_t x, uint16_t y, uint16_t width, uint16_t height, void oledfillRect(uint16_t x, uint16_t y, uint16_t width, uint16_t height,
uint8_t bRender); uint8_t bRender);

View File

@ -111,6 +111,11 @@ typedef struct {
float gas; // raw gas sensor signal float gas; // raw gas sensor signal
} bmeStatus_t; } bmeStatus_t;
typedef struct {
float pm10;
float pm25;
} sdsStatus_t;
extern std::set<uint16_t, std::less<uint16_t>, Mallocator<uint16_t>> macs; extern std::set<uint16_t, std::less<uint16_t>, Mallocator<uint16_t>> macs;
extern std::array<uint64_t, 0xff>::iterator it; extern std::array<uint64_t, 0xff>::iterator it;
extern std::array<uint64_t, 0xff> beacons; extern std::array<uint64_t, 0xff> beacons;

View File

@ -20,7 +20,7 @@ int gps_config();
bool gps_hasfix(); bool gps_hasfix();
void gps_storelocation(gpsStatus_t *gps_store); void gps_storelocation(gpsStatus_t *gps_store);
void gps_loop(void *pvParameters); void gps_loop(void *pvParameters);
time_t fetch_gpsTime(uint16_t *msec); time_t get_gpstime(uint16_t *msec);
time_t fetch_gpsTime(void); time_t get_gpstime(void);
#endif #endif

View File

@ -3,6 +3,10 @@
#include "paxcounter.conf" #include "paxcounter.conf"
#if (HAS_SDS011)
#include "sds011read.h"
#endif
// MyDevices CayenneLPP 1.0 channels for Synamic sensor payload format // MyDevices CayenneLPP 1.0 channels for Synamic sensor payload format
// all payload goes out on LoRa FPort 1 // all payload goes out on LoRa FPort 1
#if (PAYLOAD_ENCODER == 3) #if (PAYLOAD_ENCODER == 3)
@ -19,6 +23,8 @@
#define LPP_HUMIDITY_CHANNEL 29 #define LPP_HUMIDITY_CHANNEL 29
#define LPP_BAROMETER_CHANNEL 30 #define LPP_BAROMETER_CHANNEL 30
#define LPP_AIR_CHANNEL 31 #define LPP_AIR_CHANNEL 31
#define LPP_PARTMATTER10_CHANNEL 32 // particular matter for PM 10
#define LPP_PARTMATTER25_CHANNEL 33 // particular matter for PM 2.5
// MyDevices CayenneLPP 2.0 types for Packed Sensor Payload, not using channels, // MyDevices CayenneLPP 2.0 types for Packed Sensor Payload, not using channels,
// but different FPorts // but different FPorts
@ -55,6 +61,9 @@ public:
void addButton(uint8_t value); void addButton(uint8_t value);
void addSensor(uint8_t[]); void addSensor(uint8_t[]);
void addTime(time_t value); void addTime(time_t value);
void addSDS(sdsStatus_t value);
private:
void addChars( char* string, int len);
#if (PAYLOAD_ENCODER == 1) // format plain #if (PAYLOAD_ENCODER == 1) // format plain

View File

@ -10,7 +10,7 @@
#define SDCARD_FILE_NAME "paxcount.%02d" #define SDCARD_FILE_NAME "paxcount.%02d"
#define SDCARD_FILE_HEADER "date, time, wifi, bluet" #define SDCARD_FILE_HEADER "date, time, wifi, bluet"
bool sdcardInit( void ); bool sdcard_init( void );
void sdcardWriteData( uint16_t, uint16_t); void sdcardWriteData( uint16_t, uint16_t);
#endif #endif

15
include/sds011read.h Normal file
View File

@ -0,0 +1,15 @@
#ifndef _SDS011READ_H
#define _SDS011READ_H
#include "globals.h"
#include <SDS011.h>
#define SDCARD_FILE_HEADER_SDS011 ", PM10,PM25"
bool sds011_init();
void sds011_loop();
void sds011_sleep(void);
void sds011_wakeup(void);
void sds011_store(sdsStatus_t *sds_store);
#endif // _SDS011READ_H

View File

@ -20,8 +20,8 @@ enum timesync_t {
}; };
void timesync_init(void); void timesync_init(void);
void timesync_sendReq(void); void timesync_request(void);
void timesync_storeReq(uint32_t timestamp, timesync_t timestamp_type); void timesync_store(uint32_t timestamp, timesync_t timestamp_type);
void IRAM_ATTR timesync_processReq(void *taskparameter); void IRAM_ATTR timesync_processReq(void *taskparameter);
void IRAM_ATTR timesync_serverAnswer(void *pUserData, int flag); void IRAM_ATTR timesync_serverAnswer(void *pUserData, int flag);

View File

@ -45,7 +45,7 @@ description = Paxcounter is a device for metering passenger flows in realtime. I
[common] [common]
; for release_version use max. 10 chars total, use any decimal format like "a.b.c" ; for release_version use max. 10 chars total, use any decimal format like "a.b.c"
release_version = 1.9.95 release_version = 1.9.98
; DEBUG LEVEL: For production run set to 0, otherwise device will leak RAM while running! ; DEBUG LEVEL: For production run set to 0, otherwise device will leak RAM while running!
; 0=None, 1=Error, 2=Warn, 3=Info, 4=Debug, 5=Verbose ; 0=None, 1=Error, 2=Warn, 3=Info, 4=Debug, 5=Verbose
debug_level = 3 debug_level = 3
@ -59,13 +59,13 @@ upload_speed = 115200
lib_deps_lora = lib_deps_lora =
MCCI LoRaWAN LMIC library@>=3.1.0 ; MCCI LMIC by Terrill Moore MCCI LoRaWAN LMIC library@>=3.1.0 ; MCCI LMIC by Terrill Moore
lib_deps_display = lib_deps_display =
ss_oled@3.3.1 ; simple and small OLED lib by Larry Bank ss_oled@4.1.0 ; simple and small OLED lib by Larry Bank
BitBang_I2C@1.3.0 BitBang_I2C@2.0.1
QRCode@>=0.0.1 QRCode@>=0.0.1
lib_deps_matrix_display = lib_deps_matrix_display =
Ultrathin_LED_Matrix@>=1.0.0 Ultrathin_LED_Matrix@>=1.0.0
lib_deps_rgbled = lib_deps_rgbled =
SmartLeds@>=1.1.6 SmartLeds@>=1.2.0
lib_deps_gps = lib_deps_gps =
1655@>=1.0.2 ; #1655 TinyGPSPlus by Mikal Hart 1655@>=1.0.2 ; #1655 TinyGPSPlus by Mikal Hart
lib_deps_sensors = lib_deps_sensors =
@ -73,6 +73,7 @@ lib_deps_sensors =
Adafruit BME280 Library@>=2.0.0 Adafruit BME280 Library@>=2.0.0
Adafruit BMP085 Library@>=1.0.1 Adafruit BMP085 Library@>=1.0.1
BSEC Software Library@1.5.1474 BSEC Software Library@1.5.1474
https://github.com/ricki-z/SDS011.git
lib_deps_basic = lib_deps_basic =
ArduinoJson@^5.13.1 ArduinoJson@^5.13.1
76@>=1.2.4 ; #76 Timezone by Jack Christensen 76@>=1.2.4 ; #76 Timezone by Jack Christensen

View File

@ -9,6 +9,10 @@ static const char TAG[] = __FILE__;
Ticker housekeeper; Ticker housekeeper;
#if (HAS_SDS011)
extern boolean isSDS011Active;
#endif
void housekeeping() { void housekeeping() {
xTaskNotifyFromISR(irqHandlerTask, CYCLIC_IRQ, eSetBits, NULL); xTaskNotifyFromISR(irqHandlerTask, CYCLIC_IRQ, eSetBits, NULL);
} }
@ -18,7 +22,6 @@ void doHousekeeping() {
// update uptime counter // update uptime counter
uptime(); uptime();
// check if update mode trigger switch was set // check if update mode trigger switch was set
if (RTC_runmode == RUNMODE_UPDATE) { if (RTC_runmode == RUNMODE_UPDATE) {
// check battery status if we can before doing ota // check battery status if we can before doing ota
@ -112,6 +115,17 @@ void doHousekeeping() {
} }
#endif #endif
#if (HAS_SDS011)
if ( isSDS011Active ) {
ESP_LOGD(TAG, "SDS011: go to sleep");
sds011_loop();
}
else {
ESP_LOGD(TAG, "SDS011: wakeup");
sds011_wakeup();
}
#endif
} // doHousekeeping() } // doHousekeeping()
// uptime counter 64bit to prevent millis() rollover after 49 days // uptime counter 64bit to prevent millis() rollover after 49 days

View File

@ -39,19 +39,6 @@ FONT_STRETCHED: 16x32px = 8 chars / line
// local Tag for logging // local Tag for logging
static const char TAG[] = __FILE__; static const char TAG[] = __FILE__;
#define DISPLAY_PAGES (7) // number of paxcounter display pages
// settings for oled display library
#define USE_BACKBUFFER
// settings for qr code generator
#define QR_VERSION 3 // 29 x 29px
#define QR_SCALEFACTOR 2 // 29 -> 58x < 64px
// settings for curve plotter
#define DISPLAY_WIDTH 128 // Width in pixels of OLED-display, must be 32X
#define DISPLAY_HEIGHT 64 // Height in pixels of OLED-display, must be 64X
// helper array for converting month values to text // helper array for converting month values to text
const char *printmonth[] = {"xxx", "Jan", "Feb", "Mar", "Apr", "May", "Jun", const char *printmonth[] = {"xxx", "Jan", "Feb", "Mar", "Apr", "May", "Jun",
"Jul", "Aug", "Sep", "Oct", "Nov", "Dec"}; "Jul", "Aug", "Sep", "Oct", "Nov", "Dec"};
@ -60,6 +47,23 @@ uint8_t displaybuf[DISPLAY_WIDTH * DISPLAY_HEIGHT / 8] = {0};
static uint8_t plotbuf[DISPLAY_WIDTH * DISPLAY_HEIGHT / 8] = {0}; static uint8_t plotbuf[DISPLAY_WIDTH * DISPLAY_HEIGHT / 8] = {0};
QRCode qrcode; QRCode qrcode;
SSOLED ssoled;
void setup_display(int contrast) {
int rc = oledInit(&ssoled, MY_OLED, OLED_ADDR, DISPLAY_FLIP, OLED_INVERT,
USE_HW_I2C, MY_OLED_SDA, MY_OLED_SCL, MY_OLED_RST,
400000L); // use standard I2C bus at 400Khz
assert(rc != OLED_NOT_FOUND);
// set display buffer
oledSetBackBuffer(&ssoled, displaybuf);
if (contrast)
oledSetContrast(&ssoled, contrast);
// clear display
oledFill(&ssoled, 0, 1);
}
void init_display(bool verbose) { void init_display(bool verbose) {
@ -68,19 +72,7 @@ void init_display(bool verbose) {
ESP_LOGV(TAG, "[%0.3f] i2c mutex lock failed", millis() / 1000.0); ESP_LOGV(TAG, "[%0.3f] i2c mutex lock failed", millis() / 1000.0);
else { else {
// init display setup_display(DISPLAYCONTRAST);
#ifndef DISPLAY_FLIP
oledInit(OLED_128x64, false, false, -1, -1, MY_OLED_RST, 400000L);
#else
oledInit(OLED_128x64, true, false, -1, -1, MY_OLED_RST, 400000L);
#endif
// set display buffer
oledSetBackBuffer(displaybuf);
// clear display
oledSetContrast(DISPLAYCONTRAST);
oledFill(0, 1);
if (verbose) { if (verbose) {
@ -104,20 +96,20 @@ void init_display(bool verbose) {
: "ext."); : "ext.");
// give user some time to read or take picture // give user some time to read or take picture
oledDumpBuffer(displaybuf); dp_dump(displaybuf);
delay(2000); delay(2000);
oledFill(0x00, 1); oledFill(&ssoled, 0x00, 1);
#endif // VERBOSE #endif // VERBOSE
#if (HAS_LORA) #if (HAS_LORA)
// generate DEVEUI as QR code and text // generate DEVEUI as QR code and text
uint8_t buf[8]; uint8_t buf[8], *p = buf;
char deveui[17]; char deveui[17];
os_getDevEui((u1_t *)buf); os_getDevEui((u1_t *)buf);
snprintf(deveui, 17, "%016llX", *((uint64_t *)&buf)); snprintf(deveui, 17, "%016llX", (*(uint64_t *)(p)));
// display DEVEUI as QR code on the left // display DEVEUI as QR code on the left
oledSetContrast(30); oledSetContrast(&ssoled, 30);
dp_printqr(3, 3, deveui); dp_printqr(3, 3, deveui);
// display DEVEUI as plain text on the right // display DEVEUI as plain text on the right
@ -127,15 +119,15 @@ void init_display(bool verbose) {
dp_printf(80, i + 3, FONT_NORMAL, 0, "%4.4s", deveui + i * 4); dp_printf(80, i + 3, FONT_NORMAL, 0, "%4.4s", deveui + i * 4);
// give user some time to read or take picture // give user some time to read or take picture
oledDumpBuffer(displaybuf); dp_dump(displaybuf);
delay(8000); delay(8000);
oledSetContrast(DISPLAYCONTRAST); oledSetContrast(&ssoled, DISPLAYCONTRAST);
oledFill(0x00, 1); oledFill(&ssoled, 0x00, 1);
#endif // HAS_LORA #endif // HAS_LORA
} // verbose } // verbose
oledPower(cfg.screenon); // set display off if disabled oledPower(&ssoled, cfg.screenon); // set display off if disabled
I2C_MUTEX_UNLOCK(); // release i2c bus access I2C_MUTEX_UNLOCK(); // release i2c bus access
} // mutex } // mutex
@ -164,7 +156,7 @@ void refreshTheDisplay(bool nextPage) {
// set display on/off according to current device configuration // set display on/off according to current device configuration
if (DisplayIsOn != cfg.screenon) { if (DisplayIsOn != cfg.screenon) {
DisplayIsOn = cfg.screenon; DisplayIsOn = cfg.screenon;
oledPower(cfg.screenon); oledPower(&ssoled, cfg.screenon);
} }
#ifndef HAS_BUTTON #ifndef HAS_BUTTON
@ -176,7 +168,7 @@ void refreshTheDisplay(bool nextPage) {
#endif #endif
draw_page(t, nextPage); draw_page(t, nextPage);
oledDumpBuffer(displaybuf); dp_dump(displaybuf);
I2C_MUTEX_UNLOCK(); // release i2c bus access I2C_MUTEX_UNLOCK(); // release i2c bus access
@ -214,7 +206,7 @@ start:
if (nextpage) { if (nextpage) {
DisplayPage = (DisplayPage >= DISPLAY_PAGES - 1) ? 0 : (DisplayPage + 1); DisplayPage = (DisplayPage >= DISPLAY_PAGES - 1) ? 0 : (DisplayPage + 1);
oledFill(0, 1); oledFill(&ssoled, 0, 1);
} }
switch (DisplayPage) { switch (DisplayPage) {
@ -307,7 +299,7 @@ start:
// page 1: pax graph // page 1: pax graph
case 1: case 1:
oledDumpBuffer(plotbuf); dp_dump(plotbuf);
break; // page1 break; // page1
// page 2: GPS // page 2: GPS
@ -391,7 +383,7 @@ start:
// page 6: blank screen // page 6: blank screen
case 6: case 6:
#ifdef HAS_BUTTON #ifdef HAS_BUTTON
oledFill(0, 1); oledFill(&ssoled, 0, 1);
break; break;
#else // don't show blank page if we are unattended #else // don't show blank page if we are unattended
DisplayPage++; // next page DisplayPage++; // next page
@ -428,12 +420,14 @@ void dp_printf(uint16_t x, uint16_t y, uint8_t font, uint8_t inv,
len = vsnprintf(temp, len + 1, format, arg); len = vsnprintf(temp, len + 1, format, arg);
} }
va_end(arg); va_end(arg);
oledWriteString(0, x, y, temp, font, inv, false); oledWriteString(&ssoled, 0, x, y, temp, font, inv, false);
if (temp != loc_buf) { if (temp != loc_buf) {
free(temp); free(temp);
} }
} }
void dp_dump(uint8_t *pBuffer) { oledDumpBuffer(&ssoled, pBuffer); }
void dp_printqr(uint16_t offset_x, uint16_t offset_y, const char *Message) { void dp_printqr(uint16_t offset_x, uint16_t offset_y, const char *Message) {
uint8_t qrcodeData[qrcode_getBufferSize(QR_VERSION)]; uint8_t qrcodeData[qrcode_getBufferSize(QR_VERSION)];
qrcode_initText(&qrcode, qrcodeData, QR_VERSION, ECC_HIGH, Message); qrcode_initText(&qrcode, qrcodeData, QR_VERSION, ECC_HIGH, Message);
@ -460,7 +454,7 @@ void dp_printqr(uint16_t offset_x, uint16_t offset_y, const char *Message) {
void oledfillRect(uint16_t x, uint16_t y, uint16_t width, uint16_t height, void oledfillRect(uint16_t x, uint16_t y, uint16_t width, uint16_t height,
uint8_t bRender) { uint8_t bRender) {
for (uint16_t xi = x; xi < x + width; xi++) for (uint16_t xi = x; xi < x + width; xi++)
oledDrawLine(xi, y, xi, y + height - 1, bRender); oledDrawLine(&ssoled, xi, y, xi, y + height - 1, bRender);
} }
int oledDrawPixel(uint8_t *buf, const uint16_t x, const uint16_t y, int oledDrawPixel(uint8_t *buf, const uint16_t x, const uint16_t y,

View File

@ -10,8 +10,6 @@ static const char TAG[] = __FILE__;
TinyGPSPlus gps; TinyGPSPlus gps;
TinyGPSCustom gpstime(gps, "GPZDA", 1); // field 1 = UTC time TinyGPSCustom gpstime(gps, "GPZDA", 1); // field 1 = UTC time
static const String ZDA_Request = "$EIGPQ,ZDA*39\r\n"; static const String ZDA_Request = "$EIGPQ,ZDA*39\r\n";
gpsStatus_t gps_status = {0};
TaskHandle_t GpsTask; TaskHandle_t GpsTask;
#ifdef GPS_SERIAL #ifdef GPS_SERIAL
@ -92,7 +90,7 @@ bool gps_hasfix() {
} }
// function to fetch current time from struct; note: this is costly // function to fetch current time from struct; note: this is costly
time_t fetch_gpsTime(uint16_t *msec) { time_t get_gpstime(uint16_t *msec) {
time_t time_sec = 0; time_t time_sec = 0;
@ -133,11 +131,11 @@ time_t fetch_gpsTime(uint16_t *msec) {
return timeIsValid(time_sec); return timeIsValid(time_sec);
} // fetch_gpsTime() } // get_gpstime()
time_t fetch_gpsTime(void) { time_t get_gpstime(void) {
uint16_t msec; uint16_t msec;
return fetch_gpsTime(&msec); return get_gpstime(&msec);
} }
// GPS serial feed FreeRTos Task // GPS serial feed FreeRTos Task

View File

@ -48,8 +48,14 @@
//#define HAS_BMP180 //#define HAS_BMP180
//#define BMP180_ADDR 0x77 //#define BMP180_ADDR 0x77
// SDS011 dust sensor settings
#define HAS_SDS011 1 // use SDS011
// used pins on the ESP-side:
#define SDS_TX 19 // connect to RX on the SDS011
#define SDS_RX 23 // connect to TX on the SDS011
// user defined sensors // user defined sensors
//#define HAS_SENSORS 1 // comment out if device has user defined sensors #define HAS_SENSORS 1 // comment out if device has user defined sensors
#define CFG_sx1276_radio 1 // select LoRa chip #define CFG_sx1276_radio 1 // select LoRa chip
//#define CFG_sx1272_radio 1 // select LoRa chip //#define CFG_sx1272_radio 1 // select LoRa chip

View File

@ -2,26 +2,21 @@
// upload_speed 921600 // upload_speed 921600
// board m5stack-core-esp32 // board m5stack-core-esp32
// EXPERIMENTAL VERSION - NOT TESTED ON M5 HARDWARE YET
#ifndef _M5CORE_H #ifndef _M5CORE_H
#define _M5CORE_H #define _M5CORE_H
#include <stdint.h> #include <stdint.h>
#define HAS_LORA 1 // comment out if device shall not send data via LoRa or has no M5 RA01 LoRa module #define HAS_LORA 1 // comment out if device shall not send data via LoRa or has no M5 RA01 LoRa module
// Pins for LORA chip SPI interface, reset line and interrupt lines
#define LORA_SCK SCK #define LORA_SCK SCK
#define LORA_CS SS #define LORA_CS SS
#define LORA_MISO MISO #define LORA_MISO MISO
#define LORA_MOSI MOSI #define LORA_MOSI MOSI
#define LORA_RST GPIO_NUM_36 #define LORA_RST GPIO_NUM_26
#define LORA_IRQ GPIO_NUM_26 #define LORA_IRQ GPIO_NUM_36
#define LORA_IO1 GPIO_NUM_34 // must be externally wired on PCB! #define LORA_IO1 GPIO_NUM_34 // must be wired by you on PCB!
#define LORA_IO2 LMIC_UNUSED_PIN #define LORA_IO2 LMIC_UNUSED_PIN
// enable only if you want to store a local paxcount table on the device // enable only if you want to store a local paxcount table on the device
#define HAS_SDCARD 1 // this board has an SD-card-reader/writer #define HAS_SDCARD 1 // this board has an SD-card-reader/writer
// Pins for SD-card // Pins for SD-card

View File

@ -2,29 +2,24 @@
// upload_speed 921600 // upload_speed 921600
// board m5stack-fire // board m5stack-fire
// EXPERIMENTAL VERSION - NOT TESTED ON M5 HARDWARE YET
#ifndef _M5FIRE_H #ifndef _M5FIRE_H
#define _M5FIRE_H #define _M5FIRE_H
#include <stdint.h> #include <stdint.h>
// #define HAS_LORA 1 // comment out if device shall not send data via LoRa or has no M5 RA01 LoRa module #define HAS_LORA 1 // comment out if device shall not send data via LoRa or has no M5 RA01 LoRa module
// Pins for LORA chip SPI interface, reset line and interrupt lines
#define LORA_SCK SCK #define LORA_SCK SCK
#define LORA_CS SS #define LORA_CS SS
#define LORA_MISO MISO #define LORA_MISO MISO
#define LORA_MOSI MOSI #define LORA_MOSI MOSI
#define LORA_RST GPIO_NUM_36 #define LORA_RST GPIO_NUM_26
#define LORA_IRQ GPIO_NUM_26 #define LORA_IRQ GPIO_NUM_36
#define LORA_IO1 GPIO_NUM_34 // must be externally wired on PCB! #define LORA_IO1 GPIO_NUM_34 // must be wired by you on PCB!
#define LORA_IO2 LMIC_UNUSED_PIN #define LORA_IO2 LMIC_UNUSED_PIN
// enable only if you want to store a local paxcount table on the device // enable only if you want to store a local paxcount table on the device
#define HAS_SDCARD 1 // this board has an SD-card-reader/writer #define HAS_SDCARD 1 // this board has an SD-card-reader/writer
// Pins for SD-card
#define SDCARD_CS GPIO_NUM_4 #define SDCARD_CS GPIO_NUM_4
#define SDCARD_MOSI MOSI #define SDCARD_MOSI MOSI
#define SDCARD_MISO MISO #define SDCARD_MISO MISO

View File

@ -31,6 +31,9 @@
#define MY_OLED_SCL (15) #define MY_OLED_SCL (15)
#define MY_OLED_RST (16) #define MY_OLED_RST (16)
// This board reports back the wrong I2C address, so we overwrite it here
#define MY_OLED_ADDR 0x3C
// Pins for LORA chip SPI interface come from board file, we need some // Pins for LORA chip SPI interface come from board file, we need some
// additional definitions for LMIC // additional definitions for LMIC
#define LORA_IO1 (33) #define LORA_IO1 (33)

View File

@ -23,11 +23,6 @@
#define SDCARD_MISO (2) #define SDCARD_MISO (2)
#define SDCARD_SCLK (14) #define SDCARD_SCLK (14)
// enable only if device has these sensors, otherwise comment these lines
// BME280 sensor on I2C bus
//#define HAS_BME 1 // Enable BME sensors in general
//#define HAS_BME280 GPIO_NUM_21, GPIO_NUM_22 // SDA, SCL
#define HAS_DISPLAY 1 #define HAS_DISPLAY 1
#define HAS_LED (25) // green on board LED #define HAS_LED (25) // green on board LED
#define BAT_MEASURE_ADC ADC1_GPIO35_CHANNEL // battery probe GPIO pin -> ADC1_CHANNEL_7 #define BAT_MEASURE_ADC ADC1_GPIO35_CHANNEL // battery probe GPIO pin -> ADC1_CHANNEL_7

View File

@ -87,12 +87,12 @@
// implementation is optimized for speed on 32-bit processors using // implementation is optimized for speed on 32-bit processors using
// fairly big lookup tables, but it takes up big amounts of flash on the // fairly big lookup tables, but it takes up big amounts of flash on the
// AVR architecture. // AVR architecture.
#define USE_ORIGINAL_AES //#define USE_ORIGINAL_AES
// //
// This selects the AES implementation written by Ideetroon for their // This selects the AES implementation written by Ideetroon for their
// own LoRaWAN library. It also uses lookup tables, but smaller // own LoRaWAN library. It also uses lookup tables, but smaller
// byte-oriented ones, making it use a lot less flash space (but it is // byte-oriented ones, making it use a lot less flash space (but it is
// also about twice as slow as the original). // also about twice as slow as the original).
// #define USE_IDEETRON_AES #define USE_IDEETRON_AES
// //
//#define USE_MBEDTLS_AES //#define USE_MBEDTLS_AES

View File

@ -1,4 +1,7 @@
#if(HAS_LORA) #ifndef __LORACONF_H__
#define __LORACONF_H__
#if (HAS_LORA)
/************************************************************ /************************************************************
* LMIC LoRaWAN configuration * LMIC LoRaWAN configuration
@ -6,20 +9,30 @@
* Read the values from TTN console (or whatever applies), insert them here, * Read the values from TTN console (or whatever applies), insert them here,
* and rename this file to src/loraconf.h * and rename this file to src/loraconf.h
* *
* Note that DEVEUI, APPEUI and APPKEY should all be specified in MSB format. * You can configure OTAA or ABP Activation. In order to use ABP, uncomment
* (This is different from standard LMIC-Arduino which expects DEVEUI and APPEUI * (enable) the following line, but you should only do so, if you have good
* in LSB format.) * reasons for not using OTAA.
*
*************************************************************/
* Set your DEVEUI here, if you have one. You can leave this untouched, //#define LORA_ABP
* then the DEVEUI will be generated during runtime from device's MAC adress
* and will be displayed on device's screen as well as on serial console. #ifndef LORA_ABP
/************************************************************
* OTAA configuration
* *
* NOTE: Use MSB format (as displayed in TTN console, so you can cut & paste * DEVEUI, APPEUI and APPKEY should all be specified in MSB format as
* from there) * displayed in TTN console, so you can cut & paste from there. This is different
* For TTN, APPEUI in MSB format always starts with 0x70, 0xB3, 0xD5 * from standard LMIC-Arduino which expects DEVEUI and APPEUI in LSB format.
* * For TTN, APPEUI in MSB format always starts with 0x70, 0xB3, 0xD5.
* Note: If using a board with Microchip 24AA02E64 Uinique ID for deveui,
* the DEVEUI will be overwriten by the one contained in the Microchip module * Set your DEVEUI here, if your device has have a fixed one.
* If you leave this untouched, then the DEVEUI will be derived from device's
* MAC adress during startup and will be displayed on device's screen as well as
* on serial console, if you set 'verbose 1' in paxcounter.conf and
* 'debug_level 3' in platformio.ini.
* If using a board with Microchip 24AA02E64 Uinique ID for deveui, the DEVEUI
* will be overwritten by the one contained in the Microchip module.
* *
************************************************************/ ************************************************************/
@ -30,4 +43,47 @@ static const u1_t APPEUI[8] = {0x70, 0xB3, 0xD5, 0x00, 0x00, 0x00, 0x00, 0x00};
static const u1_t APPKEY[16] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, static const u1_t APPKEY[16] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}; 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00};
#endif
#ifdef LORA_ABP
/************************************************************
* ABP configuration (for development)
*
* Get your
* - Network Session Key (NWKSKEY)
* - App Session Key and your (APPSKEY)
* - Device Address (DEVADDR)
* from e.g. TTN console and replace the example values below.
*
* NOTE: Use MSB format (as displayed in TTN console, so you can cut & paste
* from there)
*
* NOTE: You may also need to adjust lorawan_abp.cpp in order to configure
* different channels and data rate channels to match your country's regulations
* and your network's settings.
*
************************************************************/
// ID of LoRaAlliance assigned Network (for a list, see e.g. here
// https://www.thethingsnetwork.org/docs/lorawan/prefix-assignments.html)
static const u1_t NETID = 0x13; // TTN
static const u1_t NWKSKEY[16] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00};
static const u1_t APPSKEY[16] = {0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00};
static const u4_t DEVADDR =
0x00000000; // <-- Change this address for every node!
// set additional ABP parameters in loraconf_abp.cpp
void setABPParamaters();
#endif
#endif // HAS_LORA #endif // HAS_LORA
#endif // __LORACONF_H__

60
src/loraconf_abp.cpp Normal file
View File

@ -0,0 +1,60 @@
#include "lorawan.h"
#include "loraconf.h"
#ifdef LORA_ABP
/** ******************************************************************
*
* See LoRaWAN Regional Parameters Document, or here:
* https://www.thethingsnetwork.org/docs/lorawan/frequency-plans.html
*
* Parameters fro TTN and comments below are taken
* from MCCI LoRaWAN LMIC library example 'ttn-abp.ino'
*
*********************************************************************/
void setABPParamaters() {
/** **************************************************************
* ************************************************************* */
#if defined(CFG_eu868)
// Set up the channels used by the Things Network, which corresponds
// to the defaults of most gateways. Without this, only three base
// channels from the LoRaWAN specification are used, which certainly
// works, so it is good for debugging, but can overload those
// frequencies, so be sure to configure the full frequency range of
// your network here (unless your network autoconfigures them).
// Setting up channels should happen after LMIC_setSession, as that
// configures the minimal channel set.
LMIC_setupChannel(0, 868100000, DR_RANGE_MAP(DR_SF12, DR_SF7), BAND_CENTI); // g-band
LMIC_setupChannel(1, 868300000, DR_RANGE_MAP(DR_SF12, DR_SF7B), BAND_CENTI); // g-band
LMIC_setupChannel(2, 868500000, DR_RANGE_MAP(DR_SF12, DR_SF7), BAND_CENTI); // g-band
LMIC_setupChannel(3, 867100000, DR_RANGE_MAP(DR_SF12, DR_SF7), BAND_CENTI); // g-band
LMIC_setupChannel(4, 867300000, DR_RANGE_MAP(DR_SF12, DR_SF7), BAND_CENTI); // g-band
LMIC_setupChannel(5, 867500000, DR_RANGE_MAP(DR_SF12, DR_SF7), BAND_CENTI); // g-band
LMIC_setupChannel(6, 867700000, DR_RANGE_MAP(DR_SF12, DR_SF7), BAND_CENTI); // g-band
LMIC_setupChannel(7, 867900000, DR_RANGE_MAP(DR_SF12, DR_SF7), BAND_CENTI); // g-band
LMIC_setupChannel(8, 868800000, DR_RANGE_MAP(DR_FSK, DR_FSK), BAND_MILLI); // g2-band
// TTN defines an additional channel at 869.525Mhz using SF9 for class B
// devices' ping slots. LMIC does not have an easy way to define set this
// frequency and support for class B is spotty and untested, so this
// frequency is not configured here.
#elif defined(CFG_us915)
// NA-US channels 0-71 are configured automatically
// but only one group of 8 should (a subband) should be active
// TTN recommends the second sub band, 1 in a zero based count.
// https://github.com/TheThingsNetwork/gateway-conf/blob/master/US-global_conf.json
LMIC_selectSubBand(1);
#endif
// Disable link check validation
LMIC_setLinkCheckMode(0);
// TTN uses SF9 for its RX2 window.
LMIC.dn2Dr = DR_SF9;
// Set data rate and transmit power for uplink
LMIC_setDrTxpow(DR_SF7,14);
}
#endif

View File

@ -136,14 +136,21 @@ void RevBytes(unsigned char *b, size_t c) {
} }
// LMIC callback functions // LMIC callback functions
void os_getDevKey(u1_t *buf) { memcpy(buf, APPKEY, 16); } void os_getDevKey(u1_t *buf) {
#ifndef LORA_ABP
memcpy(buf, APPKEY, 16);
#endif
}
void os_getArtEui(u1_t *buf) { void os_getArtEui(u1_t *buf) {
#ifndef LORA_ABP
memcpy(buf, APPEUI, 8); memcpy(buf, APPEUI, 8);
RevBytes(buf, 8); // TTN requires it in LSB First order, so we swap bytes RevBytes(buf, 8); // TTN requires it in LSB First order, so we swap bytes
#endif
} }
void os_getDevEui(u1_t *buf) { void os_getDevEui(u1_t *buf) {
#ifndef LORA_ABP
int i = 0, k = 0; int i = 0, k = 0;
memcpy(buf, DEVEUI, 8); // get fixed DEVEUI from loraconf.h memcpy(buf, DEVEUI, 8); // get fixed DEVEUI from loraconf.h
for (i = 0; i < 8; i++) { for (i = 0; i < 8; i++) {
@ -160,6 +167,7 @@ void os_getDevEui(u1_t *buf) {
get_hard_deveui(buf); get_hard_deveui(buf);
RevBytes(buf, 8); // swap bytes to LSB format RevBytes(buf, 8); // swap bytes to LSB format
#endif #endif
#endif
} }
void get_hard_deveui(uint8_t *pdeveui) { void get_hard_deveui(uint8_t *pdeveui) {
@ -251,7 +259,7 @@ void lora_send(void *pvParameters) {
// if last packet sent was a timesync request, store TX timestamp // if last packet sent was a timesync request, store TX timestamp
if (SendBuffer.MessagePort == TIMEPORT) if (SendBuffer.MessagePort == TIMEPORT)
// store LMIC time when we started transmit of timesync request // store LMIC time when we started transmit of timesync request
timesync_storeReq(osticks2ms(os_getTime()), timesync_tx); timesync_store(osticks2ms(os_getTime()), timesync_tx);
#endif #endif
ESP_LOGI(TAG, "%d byte(s) sent to LORA", SendBuffer.MessageSize); ESP_LOGI(TAG, "%d byte(s) sent to LORA", SendBuffer.MessageSize);
@ -298,6 +306,17 @@ esp_err_t lora_stack_init(bool do_join) {
&lmicTask, // task handle &lmicTask, // task handle
1); // CPU core 1); // CPU core
#ifdef LORA_ABP
// Pass ABP parameters to LMIC_setSession
LMIC_reset();
uint8_t appskey[sizeof(APPSKEY)];
uint8_t nwkskey[sizeof(NWKSKEY)];
memcpy_P(appskey, APPSKEY, sizeof(APPSKEY));
memcpy_P(nwkskey, NWKSKEY, sizeof(NWKSKEY));
LMIC_setSession (NETID, DEVADDR, nwkskey, appskey);
// These parameters are defined as macro in loraconf.h
setABPParamaters();
#else
// Start join procedure if not already joined, // Start join procedure if not already joined,
// lora_setupForNetwork(true) is called by eventhandler when joined // lora_setupForNetwork(true) is called by eventhandler when joined
// else continue current session // else continue current session
@ -310,7 +329,7 @@ esp_err_t lora_stack_init(bool do_join) {
LMIC.seqnoUp = RTCseqnoUp; LMIC.seqnoUp = RTCseqnoUp;
LMIC.seqnoDn = RTCseqnoDn; LMIC.seqnoDn = RTCseqnoDn;
} }
#endif
// start lmic send task // start lmic send task
xTaskCreatePinnedToCore(lora_send, // task function xTaskCreatePinnedToCore(lora_send, // task function
"lorasendtask", // name of task "lorasendtask", // name of task

View File

@ -323,10 +323,16 @@ void setup() {
#endif #endif
#ifdef HAS_SDCARD #ifdef HAS_SDCARD
if (sdcardInit()) if (sdcard_init())
strcat_P(features, " SD"); strcat_P(features, " SD");
#endif #endif
#if (HAS_SDS011)
ESP_LOGI(TAG, "init fine-dust-sensor");
if ( sds011_init() )
strcat_P(features, " SDS");
#endif
#if (VENDORFILTER) #if (VENDORFILTER)
strcat_P(features, " FILTER"); strcat_P(features, " FILTER");
#endif #endif
@ -449,7 +455,7 @@ void setup() {
// initialize gps time // initialize gps time
#if (HAS_GPS) #if (HAS_GPS)
fetch_gpsTime(); get_gpstime();
#endif #endif
#if (defined HAS_IF482 || defined HAS_DCF77) #if (defined HAS_IF482 || defined HAS_DCF77)

View File

@ -45,23 +45,15 @@ void start_ota_update() {
// init display // init display
#ifdef HAS_DISPLAY #ifdef HAS_DISPLAY
#ifndef DISPLAY_FLIP setup_display();
oledInit(OLED_128x64, false, false, -1, -1, MY_OLED_RST, 400000L);
#else
oledInit(OLED_128x64, true, false, -1, -1, MY_OLED_RST, 400000L);
#endif
// set display buffer
oledSetBackBuffer(displaybuf);
oledFill(0, 1);
dp_printf(0, 0, 0, 1, "SOFTWARE UPDATE"); dp_printf(0, 0, 0, 1, "SOFTWARE UPDATE");
dp_printf(0, 1, 0, 0, "WiFi connect .."); dp_printf(0, 1, 0, 0, "WiFi connect ..");
dp_printf(0, 2, 0, 0, "Has Update? .."); dp_printf(0, 2, 0, 0, "Has Update? ..");
dp_printf(0, 3, 0, 0, "Fetching .."); dp_printf(0, 3, 0, 0, "Fetching ..");
dp_printf(0, 4, 0, 0, "Downloading .."); dp_printf(0, 4, 0, 0, "Downloading ..");
dp_printf(0, 5, 0, 0, "Rebooting .."); dp_printf(0, 5, 0, 0, "Rebooting ..");
oledDumpBuffer(displaybuf); dp_dump(displaybuf);
#endif #endif
ESP_LOGI(TAG, "Starting Wifi OTA update"); ESP_LOGI(TAG, "Starting Wifi OTA update");
@ -314,7 +306,7 @@ void ota_display(const uint8_t row, const std::string status,
dp_printf(0, 7, 0, 0, " "); dp_printf(0, 7, 0, 0, " ");
dp_printf(0, 7, 0, 0, msg.substr(0, 16).c_str()); dp_printf(0, 7, 0, 0, msg.substr(0, 16).c_str());
} }
oledDumpBuffer(displaybuf); dp_dump(displaybuf);
#endif #endif
} }

View File

@ -80,7 +80,7 @@ void PayloadConvert::addStatus(uint16_t voltage, uint64_t uptime, float cputemp,
} }
void PayloadConvert::addGPS(gpsStatus_t value) { void PayloadConvert::addGPS(gpsStatus_t value) {
#if(HAS_GPS) #if (HAS_GPS)
buffer[cursor++] = (byte)((value.latitude & 0xFF000000) >> 24); buffer[cursor++] = (byte)((value.latitude & 0xFF000000) >> 24);
buffer[cursor++] = (byte)((value.latitude & 0x00FF0000) >> 16); buffer[cursor++] = (byte)((value.latitude & 0x00FF0000) >> 16);
buffer[cursor++] = (byte)((value.latitude & 0x0000FF00) >> 8); buffer[cursor++] = (byte)((value.latitude & 0x0000FF00) >> 8);
@ -100,7 +100,7 @@ void PayloadConvert::addGPS(gpsStatus_t value) {
} }
void PayloadConvert::addSensor(uint8_t buf[]) { void PayloadConvert::addSensor(uint8_t buf[]) {
#if(HAS_SENSORS) #if (HAS_SENSORS)
uint8_t length = buf[0]; uint8_t length = buf[0];
memcpy(buffer, buf + 1, length); memcpy(buffer, buf + 1, length);
cursor += length; // length of buffer cursor += length; // length of buffer
@ -108,7 +108,7 @@ void PayloadConvert::addSensor(uint8_t buf[]) {
} }
void PayloadConvert::addBME(bmeStatus_t value) { void PayloadConvert::addBME(bmeStatus_t value) {
#if(HAS_BME) #if (HAS_BME)
int16_t temperature = (int16_t)(value.temperature); // float -> int int16_t temperature = (int16_t)(value.temperature); // float -> int
uint16_t humidity = (uint16_t)(value.humidity); // float -> int uint16_t humidity = (uint16_t)(value.humidity); // float -> int
uint16_t pressure = (uint16_t)(value.pressure); // float -> int uint16_t pressure = (uint16_t)(value.pressure); // float -> int
@ -124,6 +124,16 @@ void PayloadConvert::addBME(bmeStatus_t value) {
#endif #endif
} }
void PayloadConvert::addSDS(sdsStatus_t sds) {
#if (HAS_SDS011)
char tempBuffer[10 + 1];
sprintf(tempBuffer, ",%5.1f", sds.pm10);
addChars(tempBuffer, strlen(tempBuffer));
sprintf(tempBuffer, ",%5.1f", sds.pm25);
addChars(tempBuffer, strlen(tempBuffer));
#endif // HAS_SDS011
}
void PayloadConvert::addButton(uint8_t value) { void PayloadConvert::addButton(uint8_t value) {
#ifdef HAS_BUTTON #ifdef HAS_BUTTON
buffer[cursor++] = value; buffer[cursor++] = value;
@ -193,7 +203,7 @@ void PayloadConvert::addStatus(uint16_t voltage, uint64_t uptime, float cputemp,
} }
void PayloadConvert::addGPS(gpsStatus_t value) { void PayloadConvert::addGPS(gpsStatus_t value) {
#if(HAS_GPS) #if (HAS_GPS)
writeLatLng(value.latitude, value.longitude); writeLatLng(value.latitude, value.longitude);
#if (!PAYLOAD_OPENSENSEBOX) #if (!PAYLOAD_OPENSENSEBOX)
writeUint8(value.satellites); writeUint8(value.satellites);
@ -204,7 +214,7 @@ void PayloadConvert::addGPS(gpsStatus_t value) {
} }
void PayloadConvert::addSensor(uint8_t buf[]) { void PayloadConvert::addSensor(uint8_t buf[]) {
#if(HAS_SENSORS) #if (HAS_SENSORS)
uint8_t length = buf[0]; uint8_t length = buf[0];
memcpy(buffer, buf + 1, length); memcpy(buffer, buf + 1, length);
cursor += length; // length of buffer cursor += length; // length of buffer
@ -212,7 +222,7 @@ void PayloadConvert::addSensor(uint8_t buf[]) {
} }
void PayloadConvert::addBME(bmeStatus_t value) { void PayloadConvert::addBME(bmeStatus_t value) {
#if(HAS_BME) #if (HAS_BME)
writeFloat(value.temperature); writeFloat(value.temperature);
writePressure(value.pressure); writePressure(value.pressure);
writeUFloat(value.humidity); writeUFloat(value.humidity);
@ -220,6 +230,13 @@ void PayloadConvert::addBME(bmeStatus_t value) {
#endif #endif
} }
void PayloadConvert::addSDS(sdsStatus_t sds) {
#if (HAS_SDS011)
writeUint16((uint16_t)(sds.pm10 * 10));
writeUint16((uint16_t)(sds.pm25 * 10));
#endif // HAS_SDS011
}
void PayloadConvert::addButton(uint8_t value) { void PayloadConvert::addButton(uint8_t value) {
#ifdef HAS_BUTTON #ifdef HAS_BUTTON
writeUint8(value); writeUint8(value);
@ -242,9 +259,7 @@ void PayloadConvert::uintToBytes(uint64_t value, uint8_t byteSize) {
} }
} }
void PayloadConvert::writeUptime(uint64_t uptime) { void PayloadConvert::writeUptime(uint64_t uptime) { writeUint64(uptime); }
writeUint64(uptime);
}
void PayloadConvert::writeVersion(char *version) { void PayloadConvert::writeVersion(char *version) {
memcpy(buffer + cursor, version, 10); memcpy(buffer + cursor, version, 10);
@ -265,13 +280,9 @@ void PayloadConvert::writeUint16(uint16_t i) { uintToBytes(i, 2); }
void PayloadConvert::writeUint8(uint8_t i) { uintToBytes(i, 1); } void PayloadConvert::writeUint8(uint8_t i) { uintToBytes(i, 1); }
void PayloadConvert::writeUFloat(float value) { void PayloadConvert::writeUFloat(float value) { writeUint16(value * 100); }
writeUint16(value * 100);
}
void PayloadConvert::writePressure(float value) { void PayloadConvert::writePressure(float value) { writeUint16(value * 10); }
writeUint16(value * 10);
}
/** /**
* Uses a 16bit two's complement with two decimals, so the range is * Uses a 16bit two's complement with two decimals, so the range is
@ -315,7 +326,26 @@ void PayloadConvert::writeBitmap(bool a, bool b, bool c, bool d, bool e, bool f,
void PayloadConvert::addByte(uint8_t value) { void PayloadConvert::addByte(uint8_t value) {
/* /*
not implemented not implemented
*/ } */
}
void PayloadConvert::addSDS(sdsStatus_t sds) {
#if (HAS_SDS011)
// value of PM10
#if (PAYLOAD_ENCODER == 3) // Cayenne LPP dynamic
buffer[cursor++] = LPP_PARTMATTER10_CHANNEL; // for PM10
#endif
buffer[cursor++] = LPP_LUMINOSITY; // workaround since cayenne has no data type meter
buffer[cursor++] = highByte((uint16_t)(sds.pm10 * 10));
buffer[cursor++] = lowByte((uint16_t)(sds.pm10 * 10));
// value of PM2.5
#if (PAYLOAD_ENCODER == 3) // Cayenne LPP dynamic
buffer[cursor++] = LPP_PARTMATTER25_CHANNEL; // for PM2.5
#endif
buffer[cursor++] = LPP_LUMINOSITY; // workaround since cayenne has no data type meter
buffer[cursor++] = highByte((uint16_t)(sds.pm25 * 10));
buffer[cursor++] = lowByte((uint16_t)(sds.pm25 * 10));
#endif // HAS_SDS011
void PayloadConvert::addCount(uint16_t value, uint8_t snifftype) { void PayloadConvert::addCount(uint16_t value, uint8_t snifftype) {
switch (snifftype) { switch (snifftype) {
@ -393,7 +423,7 @@ void PayloadConvert::addStatus(uint16_t voltage, uint64_t uptime, float celsius,
} }
void PayloadConvert::addGPS(gpsStatus_t value) { void PayloadConvert::addGPS(gpsStatus_t value) {
#if(HAS_GPS) #if (HAS_GPS)
int32_t lat = value.latitude / 100; int32_t lat = value.latitude / 100;
int32_t lon = value.longitude / 100; int32_t lon = value.longitude / 100;
int32_t alt = value.altitude * 100; int32_t alt = value.altitude * 100;
@ -414,18 +444,18 @@ void PayloadConvert::addGPS(gpsStatus_t value) {
} }
void PayloadConvert::addSensor(uint8_t buf[]) { void PayloadConvert::addSensor(uint8_t buf[]) {
#if(HAS_SENSORS) #if (HAS_SENSORS)
// to come // to come
/* /*
uint8_t length = buf[0]; uint8_t length = buf[0];
memcpy(buffer, buf+1, length); memcpy(buffer, buf+1, length);
cursor += length; // length of buffer cursor += length; // length of buffer
*/ */
#endif // HAS_SENSORS #endif // HAS_SENSORS
} }
void PayloadConvert::addBME(bmeStatus_t value) { void PayloadConvert::addBME(bmeStatus_t value) {
#if(HAS_BME) #if (HAS_BME)
// data value conversions to meet cayenne data type definition // data value conversions to meet cayenne data type definition
// 0.1°C per bit => -3276,7 .. +3276,7 °C // 0.1°C per bit => -3276,7 .. +3276,7 °C
@ -489,5 +519,9 @@ void PayloadConvert::addTime(time_t value) {
buffer[cursor++] = (byte)((tx_period & 0x000000FF)); buffer[cursor++] = (byte)((tx_period & 0x000000FF));
#endif #endif
} }
#endif // PAYLOAD_ENCODER
#endif void PayloadConvert::addChars(char *string, int len) {
for (int i = 0; i < len; i++)
addByte(string[i]);
}

View File

@ -13,11 +13,13 @@ static void createFile(void);
File fileSDCard; File fileSDCard;
bool sdcardInit() { bool sdcard_init() {
ESP_LOGD(TAG, "looking for SD-card..."); ESP_LOGD(TAG, "looking for SD-card...");
useSDCard = SD.begin(SDCARD_CS, SDCARD_MOSI, SDCARD_MISO, SDCARD_SCLK); useSDCard = SD.begin(SDCARD_CS, SDCARD_MOSI, SDCARD_MISO, SDCARD_SCLK);
if (useSDCard) if (useSDCard)
createFile(); createFile();
else
ESP_LOGD(TAG, "SD-card not found");
return useSDCard; return useSDCard;
} }
@ -25,6 +27,9 @@ void sdcardWriteData(uint16_t noWifi, uint16_t noBle) {
static int counterWrites = 0; static int counterWrites = 0;
char tempBuffer[12 + 1]; char tempBuffer[12 + 1];
time_t t = now(); time_t t = now();
#if (HAS_SDS011)
sdsStatus_t sds;
#endif
if (!useSDCard) if (!useSDCard)
return; return;
@ -35,7 +40,13 @@ void sdcardWriteData(uint16_t noWifi, uint16_t noBle) {
sprintf(tempBuffer, "%02d:%02d:%02d,", hour(t), minute(t), second(t)); sprintf(tempBuffer, "%02d:%02d:%02d,", hour(t), minute(t), second(t));
fileSDCard.print(tempBuffer); fileSDCard.print(tempBuffer);
sprintf(tempBuffer, "%d,%d", noWifi, noBle); sprintf(tempBuffer, "%d,%d", noWifi, noBle);
fileSDCard.println(tempBuffer); fileSDCard.print(tempBuffer);
#if (HAS_SDS011)
sds011_store(&sds);
sprintf(tempBuffer, ",%5.1f,%4.1f", sds.pm10, sds.pm25);
fileSDCard.print(tempBuffer);
#endif
fileSDCard.println();
if (++counterWrites > 2) { if (++counterWrites > 2) {
// force writing to SD-card // force writing to SD-card
@ -58,8 +69,12 @@ void createFile(void) {
ESP_LOGD(TAG, "SD: file does not exist: opening"); ESP_LOGD(TAG, "SD: file does not exist: opening");
fileSDCard = SD.open(bufferFilename, FILE_WRITE); fileSDCard = SD.open(bufferFilename, FILE_WRITE);
if (fileSDCard) { if (fileSDCard) {
ESP_LOGD(TAG, "SD: name opended: <%s>", bufferFilename); ESP_LOGD(TAG, "SD: name opened: <%s>", bufferFilename);
fileSDCard.println(SDCARD_FILE_HEADER); fileSDCard.print(SDCARD_FILE_HEADER);
#if (HAS_SDS011)
fileSDCard.print(SDCARD_FILE_HEADER_SDS011);
#endif
fileSDCard.println();
useSDCard = true; useSDCard = true;
break; break;
} }

65
src/sds011read.cpp Normal file
View File

@ -0,0 +1,65 @@
// routines for fetching data from the SDS011-sensor
#if (HAS_SDS011)
// Local logging tag
static const char TAG[] = __FILE__;
#include "sds011read.h"
#if (HAS_IF482)
#error cannot use IF482 together with SDS011 (both use UART#2)
#endif
// UART(2) is unused in this project
static HardwareSerial sdsSerial(2); // so we use it here
static SDS011 sdsSensor; // fine dust sensor
// the results of the sensor:
static float pm10, pm25;
boolean isSDS011Active;
// init
bool sds011_init() {
pm25 = pm10 = 0.0;
sdsSensor.begin(&sdsSerial, SDS_RX, SDS_TX);
sds011_sleep(); // we do sleep/wakup by ourselves
return true;
}
// reading data:
void sds011_loop() {
if (isSDS011Active) {
int sdsErrorCode = sdsSensor.read(&pm25, &pm10);
if (sdsErrorCode) {
pm25 = pm10 = 0.0;
ESP_LOGI(TAG, "SDS011 error: %d", sdsErrorCode);
} else {
ESP_LOGI(TAG, "fine-dust-values: %5.1f,%4.1f", pm10, pm25);
}
sds011_sleep();
}
return;
}
// retrieving stored data:
void sds011_store(sdsStatus_t *sds_store) {
sds_store->pm10 = pm10;
sds_store->pm25 = pm25;
}
// putting the SDS-sensor to sleep
void sds011_sleep(void) {
sdsSensor.sleep();
isSDS011Active = false;
}
// start the SDS-sensor
// needs 30 seconds for warming up
void sds011_wakeup() {
if (!isSDS011Active) {
sdsSensor.wakeup();
isSDS011Active = true;
}
}
#endif // HAS_SDS011

View File

@ -63,9 +63,12 @@ void sendData() {
uint8_t bitmask = cfg.payloadmask; uint8_t bitmask = cfg.payloadmask;
uint8_t mask = 1; uint8_t mask = 1;
#if (HAS_GPS) #if (HAS_GPS)
gpsStatus_t gps_status; gpsStatus_t gps_status;
#endif #endif
#if (HAS_SDS011)
sdsStatus_t sds_status;
#endif
while (bitmask) { while (bitmask) {
switch (bitmask & mask) { switch (bitmask & mask) {
@ -94,6 +97,10 @@ void sendData() {
payload.addCount(macs_wifi, MAC_SNIFF_WIFI); payload.addCount(macs_wifi, MAC_SNIFF_WIFI);
if (cfg.blescan) if (cfg.blescan)
payload.addCount(macs_ble, MAC_SNIFF_BLE); payload.addCount(macs_ble, MAC_SNIFF_BLE);
#endif
#if (HAS_SDS011)
sds011_store(&sds_status);
payload.addSDS(sds_status);
#endif #endif
SendPayload(COUNTERPORT, prio_normal); SendPayload(COUNTERPORT, prio_normal);
// clear counter if not in cumulative counter mode // clear counter if not in cumulative counter mode

View File

@ -16,6 +16,9 @@ static const char TAG[] = __FILE__;
const char timeSetSymbols[] = {'G', 'R', 'L', '?'}; const char timeSetSymbols[] = {'G', 'R', 'L', '?'};
#ifdef HAS_IF482 #ifdef HAS_IF482
#if (HAS_SDS011)
#error cannot use IF482 together with SDS011 (both use UART#2)
#endif
HardwareSerial IF482(2); // use UART #2 (#1 may be in use for serial GPS) HardwareSerial IF482(2); // use UART #2 (#1 may be in use for serial GPS)
#endif #endif
@ -30,30 +33,27 @@ void calibrateTime(void) {
// kick off asychronous lora timesync if we have // kick off asychronous lora timesync if we have
#if (HAS_LORA) && (TIME_SYNC_LORASERVER) || (TIME_SYNC_LORAWAN) #if (HAS_LORA) && (TIME_SYNC_LORASERVER) || (TIME_SYNC_LORAWAN)
timesync_sendReq(); timesync_request();
#endif #endif
// only if we lost time, we try to fallback to local time source RTS or GPS // (only!) if we lost time, we try to fallback to local time source RTS or GPS
if (timeSource == _unsynced) { if (timeSource == _unsynced) {
// has RTC -> fallback to RTC time // has RTC -> fallback to RTC time
#ifdef HAS_RTC #ifdef HAS_RTC
t = get_rtctime(); t = get_rtctime();
if (t) {
timeSource = _rtc; timeSource = _rtc;
goto finish;
}
#endif #endif
// no RTC -> fallback to GPS time // no RTC -> fallback to GPS time
#if (HAS_GPS) #if (HAS_GPS)
// fetch recent time from last NMEA record t = get_gpstime(&t_msec);
t = fetch_gpsTime(&t_msec);
if (t) {
timeSource = _gps; timeSource = _gps;
goto finish;
}
#endif #endif
if (t)
setMyTime((uint32_t)t, t_msec, timeSource); // set time
} // fallback } // fallback
else else
@ -61,10 +61,6 @@ void calibrateTime(void) {
// no fallback time source available -> we can't set time // no fallback time source available -> we can't set time
return; return;
finish:
setMyTime((uint32_t)t, t_msec, timeSource); // set time
} // calibrateTime() } // calibrateTime()
// adjust system time, calibrate RTC and RTC_INT pps // adjust system time, calibrate RTC and RTC_INT pps

View File

@ -42,7 +42,7 @@ void timesync_init() {
} }
// kickoff asnychronous timesync handshake // kickoff asnychronous timesync handshake
void timesync_sendReq(void) { void timesync_request(void) {
// exit if a timesync handshake is already running // exit if a timesync handshake is already running
if (timeSyncPending) if (timeSyncPending)
return; return;
@ -57,10 +57,11 @@ void timesync_sendReq(void) {
// task for processing time sync request // task for processing time sync request
void IRAM_ATTR timesync_processReq(void *taskparameter) { void IRAM_ATTR timesync_processReq(void *taskparameter) {
uint32_t rcv_seqNo = TIME_SYNC_END_FLAG, time_offset_ms; uint32_t rcv_seqNo = TIME_SYNC_END_FLAG;
uint32_t time_offset_sec = 0, time_offset_ms = 0;
// this task is an endless loop, waiting in blocked mode, until it is // this task is an endless loop, waiting in blocked mode, until it is
// unblocked by timesync_sendReq(). It then waits to be notified from // unblocked by timesync_request(). It then waits to be notified from
// timesync_serverAnswer(), which is called from LMIC each time a timestamp // timesync_serverAnswer(), which is called from LMIC each time a timestamp
// from the timesource via LORAWAN arrived. // from the timesource via LORAWAN arrived.
@ -88,13 +89,14 @@ void IRAM_ATTR timesync_processReq(void *taskparameter) {
SendPayload(TIMEPORT, prio_high); SendPayload(TIMEPORT, prio_high);
#elif (TIME_SYNC_LORAWAN) // ask network (requires LoRAWAN >= 1.0.3) #elif (TIME_SYNC_LORAWAN) // ask network (requires LoRAWAN >= 1.0.3)
LMIC_requestNetworkTime(timesync_serverAnswer, &time_sync_seqNo); LMIC_requestNetworkTime(timesync_serverAnswer, &time_sync_seqNo);
// trigger send to immediately get DevTimeAns on class A device // trigger to immediately get DevTimeAns from class A device
LMIC_sendAlive(); LMIC_sendAlive();
#endif #endif
// wait until a timestamp was received // wait until a timestamp was received
if (xTaskNotifyWait(0x00, ULONG_MAX, &rcv_seqNo, if (xTaskNotifyWait(0x00, ULONG_MAX, &rcv_seqNo,
pdMS_TO_TICKS(TIME_SYNC_TIMEOUT * 1000)) == pdFALSE) { pdMS_TO_TICKS(TIME_SYNC_TIMEOUT * 1000)) == pdFALSE) {
ESP_LOGW(TAG, "[%0.3f] Timesync aborted: timed out", millis() / 1000.0); ESP_LOGW(TAG, "[d%0.3f] Timesync aborted: timed out",
millis() / 1000.0);
goto Fail; // no timestamp received before timeout goto Fail; // no timestamp received before timeout
} }
@ -128,17 +130,20 @@ void IRAM_ATTR timesync_processReq(void *taskparameter) {
mask_user_IRQ(); mask_user_IRQ();
// calculate average time offset over the summed up difference // calculate average time offset over the summed up difference
// add msec from latest gateway time, and apply a compensation constant for
// processing times on node and gateway
time_offset_ms /= TIME_SYNC_SAMPLES; time_offset_ms /= TIME_SYNC_SAMPLES;
time_offset_ms +=
TIME_SYNC_FIXUP + timesync_timestamp[sample_idx - 1][gwtime_msec];
// calculate absolute UTC time: take latest timestamp received from // take latest timestamp received from gateway
// gateway, convert to whole seconds, round to ceil, add fraction seconds // and add time difference rounded to whole seconds
setMyTime(timesync_timestamp[sample_idx - 1][gwtime_sec] + time_offset_sec = timesync_timestamp[sample_idx - 1][gwtime_sec];
time_offset_ms / 1000, time_offset_sec += time_offset_ms / 1000;
time_offset_ms % 1000, _lora);
// add milliseconds from latest gateway time, and apply a compensation
// constant for processing times on node and gateway, strip full seconds
time_offset_ms += timesync_timestamp[sample_idx - 1][gwtime_msec];
time_offset_ms += TIME_SYNC_FIXUP;
time_offset_ms %= 1000;
setMyTime(time_offset_sec, time_offset_ms, _lora);
// send timesync end char to show timesync was successful // send timesync end char to show timesync was successful
payload.reset(); payload.reset();
@ -158,8 +163,8 @@ void IRAM_ATTR timesync_processReq(void *taskparameter) {
} }
// store incoming timestamps // store incoming timestamps
void timesync_storeReq(uint32_t timestamp, timesync_t timestamp_type) { void timesync_store(uint32_t timestamp, timesync_t timestamp_type) {
ESP_LOGD(TAG, "[%0.3f] seq#%d[%d]: timestamp(t%d)=%d", millis() / 1000.0, ESP_LOGD(TAG, "[%0.3f] seq#%d[%d]: t%d=%d", millis() / 1000.0,
time_sync_seqNo, sample_idx, timestamp_type, timestamp); time_sync_seqNo, sample_idx, timestamp_type, timestamp);
timesync_timestamp[sample_idx][timestamp_type] = timestamp; timesync_timestamp[sample_idx][timestamp_type] = timestamp;
} }
@ -171,34 +176,37 @@ void IRAM_ATTR timesync_serverAnswer(void *pUserData, int flag) {
if (!timeSyncPending) if (!timeSyncPending)
return; return;
// store LMIC time when we received the timesync answer
ostime_t rxTime = osticks2ms(os_getTime());
// mask application irq to ensure accurate timing // mask application irq to ensure accurate timing
mask_user_IRQ(); mask_user_IRQ();
int rc = 0; int rc = 0;
uint8_t rcv_seqNo = *(uint8_t *)pUserData; // cast back void parameter to a pointer
uint8_t *p = (uint8_t *)pUserData, rcv_seqNo = *p;
uint16_t timestamp_msec = 0; uint16_t timestamp_msec = 0;
uint32_t timestamp_sec = 0; uint32_t timestamp_sec = 0;
#if (TIME_SYNC_LORASERVER) #if (TIME_SYNC_LORASERVER)
// pUserData: contains pointer to payload buffer // pUserData: contains pointer (32bit) to payload buffer
// flag: length of buffer // flag: length of buffer
// store LMIC time when we received the timesync answer // Store the instant the time request of the node was received on the gateway
timesync_storeReq(osticks2ms(os_getTime()), timesync_rx); timesync_store(rxTime, timesync_rx);
// parse timesync_answer: // parse pUserData:
// byte meaning // p type meaning
// 0 sequence number (taken from node's time_sync_req) // +0 uint8_t sequence number (taken from node's time_sync_req)
// 1..4 current second (from UTC epoch) // +1 uint32_t current second (from UTC epoch)
// 5 1/250ths fractions of current second // +4 uint8_t 1/250ths fractions of current second
// swap byte order from msb to lsb, note: this is a platform dependent hack // swap byte order from msb to lsb, note: this is a platform dependent hack
timestamp_sec = __builtin_bswap32(*(uint32_t *)(pUserData + 1)); timestamp_sec = __builtin_bswap32(*(uint32_t *)(++p));
// one step being 1/250th sec * 1000 = 4msec // one step being 1/250th sec * 1000 = 4msec
timestamp_msec = *(uint8_t *)(pUserData + 5); timestamp_msec = *(p += 4) * 4;
timestamp_msec *= 4;
// if no time is available or spurious buffer then exit // if no time is available or spurious buffer then exit
if (flag != TIME_SYNC_FRAME_LENGTH) { if (flag != TIME_SYNC_FRAME_LENGTH) {
@ -215,23 +223,18 @@ void IRAM_ATTR timesync_serverAnswer(void *pUserData, int flag) {
#elif (TIME_SYNC_LORAWAN) #elif (TIME_SYNC_LORAWAN)
// pUserData: contains pointer to SeqNo // pUserData: contains pointer to SeqNo (not needed here)
// flag: indicates if we got a recent time from the network // flag: indicates if we got a recent time from the network
uint32_t delay_msec;
lmic_time_reference_t lmicTime;
if (flag != 1) { if (flag != 1) {
ESP_LOGW(TAG, "[%0.3f] Network did not answer time request", ESP_LOGW(TAG, "[%0.3f] Network did not answer time request",
millis() / 1000.0); millis() / 1000.0);
goto Exit; goto Exit;
} }
// A struct that will be populated by LMIC_getNetworkTimeReference.
// It contains the following fields:
// - tLocal: the value returned by os_GetTime() when the time
// request was sent to the gateway, and
// - tNetwork: the seconds between the GPS epoch and the time
// the gateway received the time request
lmic_time_reference_t lmicTime;
// Populate lmic_time_reference // Populate lmic_time_reference
if ((LMIC_getNetworkTimeReference(&lmicTime)) != 1) { if ((LMIC_getNetworkTimeReference(&lmicTime)) != 1) {
ESP_LOGW(TAG, "[%0.3f] Network time request failed", millis() / 1000.0); ESP_LOGW(TAG, "[%0.3f] Network time request failed", millis() / 1000.0);
@ -239,9 +242,15 @@ void IRAM_ATTR timesync_serverAnswer(void *pUserData, int flag) {
} }
// Calculate UTCTime, considering the difference between GPS and UTC time // Calculate UTCTime, considering the difference between GPS and UTC time
// epoch, and the leap seconds
timestamp_sec = lmicTime.tNetwork + GPS_UTC_DIFF; timestamp_sec = lmicTime.tNetwork + GPS_UTC_DIFF;
// Add delay between the instant the time was transmitted and the current time
timestamp_msec = osticks2ms(os_getTime() - lmicTime.tLocal); // Add the delay between the instant the time was transmitted and
// the current time
delay_msec = osticks2ms(os_getTime() - lmicTime.tLocal);
timestamp_sec += delay_msec / 1000;
timestamp_msec += delay_msec % 1000;
goto Finish; goto Finish;
#endif // (TIME_SYNC_LORAWAN) #endif // (TIME_SYNC_LORAWAN)
@ -250,8 +259,8 @@ Finish:
// check if calculated time is recent // check if calculated time is recent
if (timeIsValid(timestamp_sec)) { if (timeIsValid(timestamp_sec)) {
// store time received from gateway // store time received from gateway
timesync_storeReq(timestamp_sec, gwtime_sec); timesync_store(timestamp_sec, gwtime_sec);
timesync_storeReq(timestamp_msec, gwtime_msec); timesync_store(timestamp_msec, gwtime_msec);
// success // success
rc = 1; rc = 1;
} else { } else {