Merge pull request #845 from cyberman54/development

v3.1.0
This commit is contained in:
Verkehrsrot 2022-01-24 10:06:47 +01:00 committed by GitHub
commit 96c59124e3
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
23 changed files with 290 additions and 360 deletions

View File

@ -569,17 +569,17 @@ Send for example `83` `86` as Downlink on Port 2 to get battery status and time/
bytes 1..4 = time/date in UTC epoch seconds (LSB) bytes 1..4 = time/date in UTC epoch seconds (LSB)
byte 5 = time source & status, see below byte 5 = time source & status, see below
bits 0..3 last seen time source bits 0..3 time source
0x00 = GPS 0x00 = GPS
0x01 = RTC 0x01 = RTC
0x02 = LORA 0x02 = LORA
0x03 = unsynched (never synched) 0x03 = unsynched
0x04 = set (source unknown) 0x04 = set (source unknown)
bits 4..7 time status bits 4..7 esp32 sntp time status
0x00 = timeNotSet (never synched) 0x00 = SNTP_SYNC_STATUS_RESET
0x01 = timeNeedsSync (last sync failed) 0x01 = SNTP_SYNC_STATUS_COMPLETED
0x02 = timeSet (synched) 0x02 = SNTP_SYNC_STATUS_IN_PROGRESS
0x87 sync time/date 0x87 sync time/date

View File

@ -4,8 +4,7 @@
#include "globals.h" #include "globals.h"
#include "timekeeper.h" #include "timekeeper.h"
#define DCF77_FRAME_SIZE (60) #define set_dcfbit(b) (1ULL << (b))
#define DCF77_PULSE_LENGTH (100)
#ifdef DCF77_ACTIVE_LOW #ifdef DCF77_ACTIVE_LOW
enum dcf_pinstate { dcf_high, dcf_low }; enum dcf_pinstate { dcf_high, dcf_low };
@ -13,12 +12,7 @@ enum dcf_pinstate { dcf_high, dcf_low };
enum dcf_pinstate { dcf_low, dcf_high }; enum dcf_pinstate { dcf_low, dcf_high };
#endif #endif
enum DCF77_Pulses { dcf_Z, dcf_0, dcf_1 }; void DCF77_Pulse(uint8_t bit);
uint64_t DCF77_Frame(const struct tm t);
void DCF77_Pulse(time_t t, uint8_t const *DCFpulse);
uint8_t *IRAM_ATTR DCF77_Frame(time_t const t);
uint8_t IRAM_ATTR dec2bcd(uint8_t const dec, uint8_t const startpos, uint8_t const endpos,
uint8_t *DCFpulse);
uint8_t IRAM_ATTR setParityBit(uint8_t const p);
#endif #endif

View File

@ -5,7 +5,6 @@
#include <Arduino.h> #include <Arduino.h>
// Time functions // Time functions
#include <ezTime.h>
#include <RtcDateTime.h> #include <RtcDateTime.h>
#include <Ticker.h> #include <Ticker.h>
@ -111,6 +110,7 @@ typedef struct {
float pm25; float pm25;
} sdsStatus_t; } sdsStatus_t;
extern char clientId[20]; // unique clientID extern char clientId[20]; // unique clientID
extern time_t _COMPILETIME; // epoch build time
#endif #endif

View File

@ -21,6 +21,5 @@ 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 get_gpstime(uint16_t *msec); time_t get_gpstime(uint16_t *msec);
time_t get_gpstime(void);
#endif #endif

View File

@ -3,10 +3,11 @@
#include "globals.h" #include "globals.h"
#include "timekeeper.h" #include "timekeeper.h"
#include "esp_sntp.h"
#define IF482_FRAME_SIZE (17) #define IF482_FRAME_SIZE (17)
#define IF482_SYNC_FIXUP (10) // calibration to fixup processing time [milliseconds] #define IF482_SYNC_FIXUP (10) // calibration to fixup processing time [milliseconds]
String IRAM_ATTR IF482_Frame(time_t t); String IF482_Frame(time_t t);
#endif #endif

View File

@ -1,17 +0,0 @@
#ifndef _MOBALINE_H
#define _MOBALINE_H
#include "globals.h"
#include "timekeeper.h"
#include "dcf77.h"
#define MOBALINE_FRAME_SIZE (33)
#define MOBALINE_PULSE_LENGTH (100)
#define MOBALINE_HEAD_PULSE_LENGTH (1500)
void MOBALINE_Pulse(time_t t, uint8_t const *DCFpulse);
uint8_t *IRAM_ATTR MOBALINE_Frame(time_t const t);
void IRAM_ATTR dec2bcd(uint8_t const dec, uint8_t const startpos,
uint8_t const endpos, uint8_t *DCFpulse);
#endif

View File

@ -10,6 +10,7 @@
#include "sensor.h" #include "sensor.h"
#include "cyclic.h" #include "cyclic.h"
#include "timekeeper.h" #include "timekeeper.h"
#include "esp_sntp.h"
#include "timesync.h" #include "timesync.h"
#include "power.h" #include "power.h"
#include "antenna.h" #include "antenna.h"

View File

@ -8,6 +8,11 @@
#include "gpsread.h" #include "gpsread.h"
#include "if482.h" #include "if482.h"
#include "dcf77.h" #include "dcf77.h"
#include "esp_sntp.h"
#define SECS_YR_2000 (946684800UL) // the time at the start of y2k
#define GPS_UTC_DIFF 315964800UL // seconds diff between gps and utc epoch
#define LEAP_SECS_SINCE_GPSEPOCH 18UL // state of 2021
enum timesource_t { _gps, _rtc, _lora, _unsynced, _set }; enum timesource_t { _gps, _rtc, _lora, _unsynced, _set };
@ -15,7 +20,6 @@ extern const char timeSetSymbols[];
extern Ticker timesyncer; extern Ticker timesyncer;
extern timesource_t timeSource; extern timesource_t timeSource;
extern TaskHandle_t ClockTask; extern TaskHandle_t ClockTask;
extern Timezone myTZ;
extern bool volatile TimePulseTick; // 1sec pps flag set by GPS or RTC extern bool volatile TimePulseTick; // 1sec pps flag set by GPS or RTC
extern hw_timer_t *ppsIRQ; extern hw_timer_t *ppsIRQ;
@ -25,11 +29,12 @@ void clock_loop(void *pvParameters);
void timepulse_start(void); void timepulse_start(void);
void setTimeSyncIRQ(void); void setTimeSyncIRQ(void);
uint8_t timepulse_init(void); uint8_t timepulse_init(void);
time_t timeIsValid(time_t const t); bool timeIsValid(time_t const t);
void calibrateTime(void); void calibrateTime(void);
void IRAM_ATTR setMyTime(uint32_t t_sec, uint16_t t_msec, void IRAM_ATTR setMyTime(uint32_t t_sec, uint16_t t_msec,
timesource_t mytimesource); timesource_t mytimesource);
time_t compiledUTC(void); time_t compileTime(const String compile_date);
time_t mkgmtime(const struct tm *ptm);
TickType_t tx_Ticks(uint32_t framesize, unsigned long baud, uint32_t config, TickType_t tx_Ticks(uint32_t framesize, unsigned long baud, uint32_t config,
int8_t rxPin, int8_t txPins); int8_t rxPin, int8_t txPins);

View File

@ -9,8 +9,6 @@
#define TIME_SYNC_FIXUP 25 // compensation for processing time [milliseconds] #define TIME_SYNC_FIXUP 25 // compensation for processing time [milliseconds]
#define TIME_SYNC_MAX_SEQNO 0xfe // threshold for wrap around time_sync_seqNo #define TIME_SYNC_MAX_SEQNO 0xfe // threshold for wrap around time_sync_seqNo
#define TIME_SYNC_END_FLAG (TIME_SYNC_MAX_SEQNO + 1) // end of handshake marker #define TIME_SYNC_END_FLAG (TIME_SYNC_MAX_SEQNO + 1) // end of handshake marker
#define GPS_UTC_DIFF 315964800UL // seconds diff between gps and utc epoch
#define LEAP_SECS_SINCE_GPSEPOCH 18UL // state of 2021
enum timesync_t { enum timesync_t {
timesync_tx, timesync_tx,

View File

@ -48,7 +48,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 = 3.0.3 release_version = 3.1.0
; 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
@ -82,7 +82,6 @@ lib_deps_basic =
https://github.com/dbSuS/libpax.git @ ^1.0.0 https://github.com/dbSuS/libpax.git @ ^1.0.0
https://github.com/SukkoPera/Arduino-Rokkit-Hash.git https://github.com/SukkoPera/Arduino-Rokkit-Hash.git
bblanchon/ArduinoJson @ ^6 bblanchon/ArduinoJson @ ^6
ropg/ezTime @ ^0.8.3
makuna/RTC @ ^2.3.5 makuna/RTC @ ^2.3.5
spacehuhn/SimpleButton spacehuhn/SimpleButton
lewisxhe/AXP202X_Library @ ^1.1.3 lewisxhe/AXP202X_Library @ ^1.1.3

View File

@ -17,104 +17,96 @@ https://github.com/udoklein/dcf77
static const char TAG[] = __FILE__; static const char TAG[] = __FILE__;
// triggered by second timepulse to ticker out DCF signal // triggered by second timepulse to ticker out DCF signal
void DCF77_Pulse(time_t t, uint8_t const *DCFpulse) { void DCF77_Pulse(uint8_t bit) {
TickType_t startTime = xTaskGetTickCount(); TickType_t startTime;
uint8_t sec = myTZ.second(t);
ESP_LOGD(TAG, "[%s] DCF second: %d", myTZ.dateTime("H:i:s.v").c_str(), sec);
// induce a DCF Pulse // induce a DCF Pulse
for (uint8_t pulse = 0; pulse <= 2; pulse++) { for (uint8_t pulseLength = 0; pulseLength <= 2; pulseLength++) {
switch (pulse) { startTime = xTaskGetTickCount(); // reference time pulse start
case 0: // start of second -> start of timeframe for logic signal switch (pulseLength) {
if (DCFpulse[sec] != dcf_Z)
digitalWrite(HAS_DCF77, dcf_low); case 0: // 0ms = start of pulse
digitalWrite(HAS_DCF77, dcf_low);
break; break;
case 1: // 100ms after start of second -> end of timeframe for logic 0 case 1: // 100ms = logic 0
if (DCFpulse[sec] == dcf_0) if (bit == 0)
digitalWrite(HAS_DCF77, dcf_high); digitalWrite(HAS_DCF77, dcf_high);
break; break;
case 2: // 200ms after start of second -> end of timeframe for logic 1 case 2: // 200ms = logic 1
digitalWrite(HAS_DCF77, dcf_high); digitalWrite(HAS_DCF77, dcf_high);
break; break;
} // switch } // switch
// pulse pause // delay to genrate pulseLength
vTaskDelayUntil(&startTime, pdMS_TO_TICKS(DCF77_PULSE_LENGTH)); vTaskDelayUntil(&startTime, pdMS_TO_TICKS(100));
} // for } // for
} // DCF77_Pulse() } // DCF77_Pulse()
uint8_t *IRAM_ATTR DCF77_Frame(time_t const t) { // helper function to convert decimal to bcd digit
uint64_t dec2bcd(uint8_t const dec, uint8_t const startpos,
uint8_t const endpos, uint8_t *odd_parity) {
// array of dcf pulses for one minute, secs 0..16 and 20 are never touched, so uint8_t data = (dec < 10) ? dec : ((dec / 10) << 4) + (dec % 10);
// we keep them statically to avoid same recalculation every minute uint64_t bcd = 0;
static uint8_t DCFpulse[DCF77_FRAME_SIZE + 1] = { *odd_parity = 0;
dcf_0, dcf_0, dcf_0, dcf_0, dcf_0, dcf_0, dcf_0, for (uint8_t i = startpos; i <= endpos; i++) {
dcf_0, dcf_0, dcf_0, dcf_0, dcf_0, dcf_0, dcf_0, bcd += (data & 1) ? set_dcfbit(i) : 0;
dcf_0, dcf_0, dcf_0, dcf_0, dcf_0, dcf_0, dcf_1}; *odd_parity += (data & 1);
data >>= 1;
}
*odd_parity %= 2;
uint8_t Parity; return bcd;
}
// ENCODE DST CHANGE ANNOUNCEMENT (Sec 16) // generates a 1 minute dcf pulse frame for calendar time t
DCFpulse[16] = dcf_0; // not yet implemented uint64_t DCF77_Frame(const struct tm t) {
// ENCODE DAYLIGHTSAVING (secs 17..18) uint8_t parity = 0, parity_sum = 0;
DCFpulse[17] = myTZ.isDST(t) ? dcf_1 : dcf_0; uint64_t frame = 0; // start with all bits 0
DCFpulse[18] = myTZ.isDST(t) ? dcf_0 : dcf_1;
// ENCODE MINUTE (secs 21..28) // DST CHANGE ANNOUNCEMENT (16)
Parity = dec2bcd(myTZ.minute(t), 21, 27, DCFpulse); // -- not implemented --
DCFpulse[28] = setParityBit(Parity);
// ENCODE HOUR (secs 29..35) // DAYLIGHTSAVING (17, 18)
Parity = dec2bcd(myTZ.hour(t), 29, 34, DCFpulse); // "01" = MEZ / "10" = MESZ
DCFpulse[35] = setParityBit(Parity); frame += t.tm_isdst > 0 ? set_dcfbit(17) : set_dcfbit(18);
// ENCODE DATE (secs 36..58) // LEAP SECOND (19)
Parity = dec2bcd(myTZ.day(t), 36, 41, DCFpulse); // -- not implemented --
Parity += dec2bcd((myTZ.weekday(t) - 1) ? (myTZ.weekday(t) - 1) : 7, 42, 44,
DCFpulse);
Parity += dec2bcd(myTZ.month(t), 45, 49, DCFpulse);
Parity += dec2bcd(myTZ.year(t) - 2000, 50, 57, DCFpulse);
DCFpulse[58] = setParityBit(Parity);
// ENCODE MARK (sec 59) // BEGIN OF TIME INFORMATION (20)
DCFpulse[59] = dcf_Z; // !! missing code here for leap second !! frame += set_dcfbit(20);
// timestamp this frame with it's minute // MINUTE (21..28)
DCFpulse[60] = myTZ.minute(t); frame += dec2bcd(t.tm_min, 21, 27, &parity);
frame += parity ? set_dcfbit(28) : 0;
return DCFpulse; // HOUR (29..35)
frame += dec2bcd(t.tm_hour, 29, 34, &parity);
frame += parity ? set_dcfbit(35) : 0;
// DATE (36..58)
frame += dec2bcd(t.tm_mday, 36, 41, &parity);
parity_sum += parity;
frame += dec2bcd((t.tm_wday == 0) ? 7 : t.tm_wday, 42, 44, &parity);
parity_sum += parity;
frame += dec2bcd(t.tm_mon + 1, 45, 49, &parity);
parity_sum += parity;
frame += dec2bcd(t.tm_year + 1900 - 2000, 50, 57, &parity);
parity_sum += parity;
frame += parity_sum % 2 ? set_dcfbit(58) : 0;
return frame;
} // DCF77_Frame() } // DCF77_Frame()
// helper function to convert decimal to bcd digit
uint8_t IRAM_ATTR dec2bcd(uint8_t const dec, uint8_t const startpos,
uint8_t const endpos, uint8_t *DCFpulse) {
uint8_t data = (dec < 10) ? dec : ((dec / 10) << 4) + (dec % 10);
uint8_t parity = 0;
for (uint8_t i = startpos; i <= endpos; i++) {
DCFpulse[i] = (data & 1) ? dcf_1 : dcf_0;
parity += (data & 1);
data >>= 1;
}
return parity;
}
// helper function to encode parity
uint8_t IRAM_ATTR setParityBit(uint8_t const p) {
return ((p & 1) ? dcf_1 : dcf_0);
}
#endif // HAS_DCF77 #endif // HAS_DCF77

View File

@ -220,7 +220,10 @@ void dp_drawPage(bool nextpage) {
// nextpage = true -> flip 1 page // nextpage = true -> flip 1 page
static uint8_t DisplayPage = 0; static uint8_t DisplayPage = 0;
char timeState; char timeState, strftime_buf[64];
time_t now;
struct tm timeinfo = {0};
#if (HAS_GPS) #if (HAS_GPS)
static bool wasnofix = true; static bool wasnofix = true;
#endif #endif
@ -320,11 +323,15 @@ void dp_drawPage(bool nextpage) {
dp_println(); dp_println();
// line 6: time + date // line 6: time + date
// 27.Feb 2019 20:27:00* // Wed Jan 12 21:49:08 *
#if (TIME_SYNC_INTERVAL) #if (TIME_SYNC_INTERVAL)
timeState = TimePulseTick ? ' ' : timeSetSymbols[timeSource]; timeState = TimePulseTick ? ' ' : timeSetSymbols[timeSource];
TimePulseTick = false; TimePulseTick = false;
dp_printf("%s", myTZ.dateTime("d.M Y H:i:s").c_str()); time(&now);
localtime_r(&now, &timeinfo);
strftime(strftime_buf, sizeof(strftime_buf), "%c", &timeinfo);
dp_printf("%.20s", strftime_buf);
// display inverse timeState if clock controller is enabled // display inverse timeState if clock controller is enabled
#if (defined HAS_DCF77) || (defined HAS_IF482) #if (defined HAS_DCF77) || (defined HAS_IF482)
@ -442,7 +449,10 @@ void dp_drawPage(bool nextpage) {
dp_setFont(MY_FONT_LARGE); dp_setFont(MY_FONT_LARGE);
dp_setTextCursor(0, 4); dp_setTextCursor(0, 4);
dp_printf("%s", myTZ.dateTime("H:i:s").c_str()); time(&now);
localtime_r(&now, &timeinfo);
strftime(strftime_buf, sizeof(strftime_buf), "%T", &timeinfo);
dp_printf("%.8s", strftime_buf);
break; break;
// ---------- page 5: pax graph ---------- // ---------- page 5: pax graph ----------

View File

@ -89,7 +89,7 @@ bool gps_hasfix() {
gps.altitude.age() < 4000); gps.altitude.age() < 4000);
} }
// function to poll current time from GPS data; note: this is costly // function to poll UTC time from GPS NMEA data; note: this is costly
time_t get_gpstime(uint16_t *msec) { time_t get_gpstime(uint16_t *msec) {
// poll NMEA ZDA sentence // poll NMEA ZDA sentence
@ -104,27 +104,26 @@ time_t get_gpstime(uint16_t *msec) {
// did we get a current date & time? // did we get a current date & time?
if (gpstime.isValid()) { if (gpstime.isValid()) {
time_t t = 0;
tmElements_t tm;
uint32_t delay_ms = uint32_t delay_ms =
gpstime.age() + nmea_txDelay_ms + NMEA_COMPENSATION_FACTOR; gpstime.age() + nmea_txDelay_ms + NMEA_COMPENSATION_FACTOR;
uint32_t zdatime = atof(gpstime.value()); uint32_t zdatime = atof(gpstime.value());
// convert time to maketime format and make time // convert UTC time from gps NMEA ZDA sentence to tm format
tm.Second = zdatime % 100; // second struct tm gps_tm = {0};
tm.Minute = (zdatime / 100) % 100; // minute gps_tm.tm_sec = zdatime % 100; // second (UTC)
tm.Hour = zdatime / 10000; // hour gps_tm.tm_min = (zdatime / 100) % 100; // minute (UTC)
tm.Day = atoi(gpsday.value()); // day gps_tm.tm_hour = zdatime / 10000; // hour (UTC)
tm.Month = atoi(gpsmonth.value()); // month gps_tm.tm_mday = atoi(gpsday.value()); // day, 01 to 31
tm.Year = atoi(gpsyear.value()) - 1970; // year offset from 1970 gps_tm.tm_mon = atoi(gpsmonth.value()) - 1; // month, 01 to 12
t = makeTime(tm); gps_tm.tm_year = atoi(gpsyear.value()) - 1900; // year, YYYY
ESP_LOGD(TAG, "GPS date/time: %s", // convert UTC tm to time_t epoch
UTC.dateTime(t, "d.M Y H:i:s.v T").c_str()); gps_tm.tm_isdst = 0; // UTC has no DST
time_t t = mkgmtime(&gps_tm);
// add protocol delay with millisecond precision // add protocol delay with millisecond precision
t += delay_ms / 1000 - 1; // whole seconds t += (time_t)(delay_ms / 1000);
*msec = delay_ms % 1000; // fractional seconds *msec = delay_ms % 1000; // fractional seconds
return t; return t;
} }
@ -135,11 +134,6 @@ time_t get_gpstime(uint16_t *msec) {
} // get_gpstime() } // get_gpstime()
time_t get_gpstime(void) {
uint16_t msec;
return get_gpstime(&msec);
}
// GPS serial feed FreeRTos Task // GPS serial feed FreeRTos Task
void gps_loop(void *pvParameters) { void gps_loop(void *pvParameters) {
@ -152,12 +146,14 @@ void gps_loop(void *pvParameters) {
// feed GPS decoder with serial NMEA data from GPS device // feed GPS decoder with serial NMEA data from GPS device
while (GPS_Serial.available()) { while (GPS_Serial.available()) {
gps.encode(GPS_Serial.read()); gps.encode(GPS_Serial.read());
yield();
} }
#elif defined GPS_I2C #elif defined GPS_I2C
Wire.requestFrom(GPS_ADDR, 32); // caution: this is a blocking call Wire.requestFrom(GPS_ADDR, 32); // caution: this is a blocking call
while (Wire.available()) { while (Wire.available()) {
gps.encode(Wire.read()); gps.encode(Wire.read());
delay(2); // 2ms delay according L76 datasheet delay(2); // 2ms delay according L76 datasheet
yield();
} }
#endif #endif
@ -165,18 +161,18 @@ void gps_loop(void *pvParameters) {
// GPS time, we trigger a device time update to poll time from GPS // GPS time, we trigger a device time update to poll time from GPS
if ((timeSource == _unsynced || timeSource == _set) && if ((timeSource == _unsynced || timeSource == _set) &&
(gpstime.isUpdated() && gpstime.isValid() && gpstime.age() < 1000)) { (gpstime.isUpdated() && gpstime.isValid() && gpstime.age() < 1000)) {
now();
calibrateTime(); calibrateTime();
} }
} // if } // if
// show NMEA data in verbose mode, useful only for debugging GPS, very noisy // show NMEA data in verbose mode, useful only for debugging GPS, very
// ESP_LOGV(TAG, "GPS NMEA data: passed %u / failed: %u / with fix: %u", // noisy ESP_LOGV(TAG, "GPS NMEA data: passed %u / failed: %u / with fix:
// %u",
// gps.passedChecksum(), gps.failedChecksum(), // gps.passedChecksum(), gps.failedChecksum(),
// gps.sentencesWithFix()); // gps.sentencesWithFix());
delay(2); // yield to CPU yield(); // yield to CPU
} // end of infinite loop } // end of infinite loop

View File

@ -84,27 +84,20 @@ not evaluated by model BU-190, use "F" instead for this model
// Local logging tag // Local logging tag
static const char TAG[] = __FILE__; static const char TAG[] = __FILE__;
String IRAM_ATTR IF482_Frame(time_t t) { String IF482_Frame(time_t t) {
char mon, out[IF482_FRAME_SIZE + 1]; char mon, out[IF482_FRAME_SIZE + 1];
switch (timeStatus()) { // indicates if time has been set and recently synced if (sntp_get_sync_status() == SNTP_SYNC_STATUS_IN_PROGRESS)
case timeSet: // time is set and is synced mon = 'M'; // time had been set but sync not completed
mon = 'A'; else
break; mon = 'A'; // time has been set and was recently synced
case timeNeedsSync: // time had been set but sync attempt did not succeed
mon = 'M';
break;
default: // unknown time status (should never be reached)
mon = '?';
break;
} // switch
// generate IF482 telegram // generate IF482 telegram
snprintf(out, sizeof(out), "O%cL%s\r", mon, myTZ.dateTime(t, UTC_TIME, "ymdwHis").c_str()); // snprintf(out, sizeof(out), "O%cL%s\r", mon, myTZ.dateTime(t, UTC_TIME,
// "ymdwHis").c_str());
ESP_LOGD(TAG, "[%s] IF482 date/time: %s", myTZ.dateTime("H:i:s.v").c_str(), // ESP_LOGD(TAG, "[%s] IF482 date/time: %s", ctime(time(NULL), out);
out);
return out; return out;
} }

View File

@ -51,7 +51,6 @@ void irqHandler(void *pvParameters) {
#if (TIME_SYNC_INTERVAL) #if (TIME_SYNC_INTERVAL)
// is time to be synced? // is time to be synced?
if (irqSource & TIMESYNC_IRQ) { if (irqSource & TIMESYNC_IRQ) {
now(); // ensure sysTime is recent
calibrateTime(); calibrateTime();
} }
#endif #endif

View File

@ -12,7 +12,7 @@ static const char TAG[] = __FILE__;
uint8_t MatrixDisplayIsOn = 0; uint8_t MatrixDisplayIsOn = 0;
static uint8_t displaybuf[LED_MATRIX_WIDTH * LED_MATRIX_HEIGHT / 8] = {0}; static uint8_t displaybuf[LED_MATRIX_WIDTH * LED_MATRIX_HEIGHT / 8] = {0};
static unsigned long ulLastNumMacs = 0; static unsigned long ulLastNumMacs = 0;
static time_t ulLastTime = now(); static time_t ulLastTime = time(NULL);
hw_timer_t *matrixDisplayIRQ = NULL; hw_timer_t *matrixDisplayIRQ = NULL;
@ -116,11 +116,11 @@ void refreshTheMatrixDisplay(bool nextPage) {
case 1: case 1:
const time_t t = now(); const time_t t = time(NULL);
if (ulLastTime != t) { if (ulLastTime != t) {
ulLastTime = t; ulLastTime = t;
matrix.clear(); matrix.clear();
DrawNumber(myTZ.dateTime("H:i:s").c_str()); //DrawNumber(myTZ.dateTime("H:i:s").c_str());
} }
break; break;

View File

@ -126,6 +126,7 @@ void setup() {
snprintf(clientId, 20, "paxcounter_%08x", hashedmac); snprintf(clientId, 20, "paxcounter_%08x", hashedmac);
ESP_LOGI(TAG, "Starting %s v%s (runmode=%d / restarts=%d)", clientId, ESP_LOGI(TAG, "Starting %s v%s (runmode=%d / restarts=%d)", clientId,
PROGVERSION, RTC_runmode, RTC_restarts); PROGVERSION, RTC_runmode, RTC_restarts);
ESP_LOGI(TAG, "code build date: %d", _COMPILETIME);
// print chip information on startup if in verbose mode after coldstart // print chip information on startup if in verbose mode after coldstart
#if (VERBOSE) #if (VERBOSE)
@ -448,7 +449,7 @@ void setup() {
ESP_LOGI(TAG, "BME sensor initialized"); ESP_LOGI(TAG, "BME sensor initialized");
else { else {
ESP_LOGE(TAG, "BME sensor could not be initialized"); ESP_LOGE(TAG, "BME sensor could not be initialized");
cfg.payloadmask &= ~MEMS_DATA; // switch off transmit of BME data cfg.payloadmask &= (uint8_t)~MEMS_DATA; // switch off transmit of BME data
} }
#endif #endif

View File

@ -1,108 +0,0 @@
/*
// Emulate a MOBATIME serial clock controller
//
// Protocol published and described here:
//
//
http://www.elektrorevue.cz/cz/download/time-distribution-within-industry-4-0-platform--controlling-slave-clocks-via-master-clock-hn50/
*/
#ifdef HAS_MOBALINE
#include "mobaline.h"
// Local logging tag
static const char TAG[] = __FILE__;
// triggered by pulse per second to ticker out mobaline frame
void MOBALINE_Pulse(time_t t, uint8_t const *DCFpulse) {
TickType_t startTime = xTaskGetTickCount();
uint8_t sec = myTZ.second(t);
ESP_LOGD(TAG, "[%s] MOBALINE sec: %d", myTZ.dateTime("H:i:s.v").c_str(),
sec);
// induce 3 pulses
for (uint8_t pulse = 0; pulse <= 3; pulse++) {
switch (pulse) {
case 0: // start of bit -> start of timeframe for logic signal
if (DCFpulse[sec] != dcf_Z) {
digitalWrite(HAS_DCF77, dcf_high);
vTaskDelay(pdMS_TO_TICKS(MOBALINE_HEAD_PULSE_LENGTH));
digitalWrite(HAS_DCF77, dcf_high);
vTaskDelay(pdMS_TO_TICKS(MOBALINE_HEAD_PULSE_LENGTH));
return; // next bit
} else // start the signalling for the next bit
digitalWrite(HAS_DCF77, dcf_high);
break;
case 1: // 100ms after start of bit -> end of timeframe for logic 0
if (DCFpulse[sec] == dcf_1)
digitalWrite(HAS_DCF77, dcf_low);
break;
case 2: // 200ms after start of bit -> end of timeframe for logic 1
if (DCFpulse[sec] == dcf_0)
digitalWrite(HAS_DCF77, dcf_low);
break;
case 3: // 300ms after start -> last pulse
break;
} // switch
// pulse pause
vTaskDelayUntil(&startTime, pdMS_TO_TICKS(MOBALINE_PULSE_LENGTH));
} // for
} // DCF77_Pulse()
uint8_t *IRAM_ATTR MOBALINE_Frame(time_t const tt) {
// array of dcf pulses for one minute, secs 0..16 and 20 are never touched, so
// we keep them statically to avoid same recalculation every minute
static uint8_t DCFpulse[DCF77_FRAME_SIZE + 1];
time_t t = myTZ.tzTime(tt); // convert to local time
// ENCODE HEAD (bit 0))
DCFpulse[0] = dcf_Z; // not yet implemented
// ENCODE DAYLIGHTSAVING (bit 1)
DCFpulse[1] = myTZ.isDST(t) ? dcf_1 : dcf_0;
// ENCODE DATE (bits 2..20)
dec2bcd(false, year(t) - 2000, 2, 9, DCFpulse);
dec2bcd(false, month(t), 10, 14, DCFpulse);
dec2bcd(false, day(t), 15, 20, DCFpulse);
// ENCODE HOUR (bits 21..26)
dec2bcd2(false, hour(t), 21, 26, DCFpulse);
// ENCODE MINUTE (bits 27..33)
dec2bcd2(false, minute(t), 27, 33, DCFpulse);
// timestamp this frame with it's minute
DCFpulse[34] = minute(t);
return DCFpulse;
} // MOBALINE_Frame()
// helper function to convert decimal to bcd digit msb
void IRAM_ATTR dec2bcd(uint8_t const dec, uint8_t const startpos,
uint8_t const endpos, uint8_t *DCFpulse) {
uint8_t data = (dec < 10) ? dec : ((dec / 10) << 4) + (dec % 10);
for (uint8_t i = endpos; i >= startpos; i--) {
DCFpulse[i] = (data & 1) ? dcf_1 : dcf_0;
data >>= 1;
}
}
#endif // HAS_MOBALINE

View File

@ -372,10 +372,10 @@ void get_batt(uint8_t val[]) {
void get_time(uint8_t val[]) { void get_time(uint8_t val[]) {
ESP_LOGI(TAG, "Remote command: get time"); ESP_LOGI(TAG, "Remote command: get time");
time_t t = now(); time_t t = time(NULL);
payload.reset(); payload.reset();
payload.addTime(t); payload.addTime(t);
payload.addByte(timeStatus() << 4 | timeSource); payload.addByte(sntp_get_sync_status() << 4 | timeSource);
SendPayload(TIMEPORT); SendPayload(TIMEPORT);
}; };
@ -401,9 +401,9 @@ void set_enscount(uint8_t val[]) {
ESP_LOGI(TAG, "Remote command: set ENS_COUNT to %s", val[0] ? "on" : "off"); ESP_LOGI(TAG, "Remote command: set ENS_COUNT to %s", val[0] ? "on" : "off");
cfg.enscount = val[0] ? 1 : 0; cfg.enscount = val[0] ? 1 : 0;
if (val[0]) if (val[0])
cfg.payloadmask |= SENSOR1_DATA; cfg.payloadmask |= (uint8_t)SENSOR1_DATA;
else else
cfg.payloadmask &= ~SENSOR1_DATA; cfg.payloadmask &= (uint8_t)~SENSOR1_DATA;
} }
void set_loadconfig(uint8_t val[]) { void set_loadconfig(uint8_t val[]) {

View File

@ -15,7 +15,6 @@ RTC_NOINIT_ATTR uint32_t RTC_restarts;
// RTC_DATA_ATTR -> keep values after a wakeup from sleep // RTC_DATA_ATTR -> keep values after a wakeup from sleep
RTC_DATA_ATTR struct timeval RTC_sleep_start_time; RTC_DATA_ATTR struct timeval RTC_sleep_start_time;
RTC_DATA_ATTR unsigned long long RTC_millis = 0; RTC_DATA_ATTR unsigned long long RTC_millis = 0;
RTC_DATA_ATTR time_t RTC_time = 0;
timeval sleep_stop_time; timeval sleep_stop_time;
@ -49,8 +48,9 @@ void do_after_reset(void) {
// set time zone to user value from paxcounter.conf // set time zone to user value from paxcounter.conf
#ifdef TIME_SYNC_TIMEZONE #ifdef TIME_SYNC_TIMEZONE
myTZ.setPosix(TIME_SYNC_TIMEZONE); setenv("TZ", TIME_SYNC_TIMEZONE, 1);
ESP_LOGD(TAG, "Timezone set to %s", myTZ.getPosix().c_str()); tzset();
ESP_LOGD(TAG, "Timezone set to %s", TIME_SYNC_TIMEZONE);
#endif #endif
switch (rtc_get_reset_reason(0)) { switch (rtc_get_reset_reason(0)) {
@ -75,8 +75,8 @@ void do_after_reset(void) {
RTC_millis += sleep_time_ms; // increment system monotonic time RTC_millis += sleep_time_ms; // increment system monotonic time
ESP_LOGI(TAG, "Time spent in deep sleep: %d ms", sleep_time_ms); ESP_LOGI(TAG, "Time spent in deep sleep: %d ms", sleep_time_ms);
// restore time // do we have a valid time? -> set global variable
setMyTime(RTC_time, sleep_time_ms, _set); timeSource = timeIsValid(sleep_stop_time.tv_sec) ? _set : _unsynced;
// set wakeup state, not if we have pending OTA update // set wakeup state, not if we have pending OTA update
if (RTC_runmode == RUNMODE_SLEEP) if (RTC_runmode == RUNMODE_SLEEP)
@ -196,7 +196,6 @@ void enter_deepsleep(const uint64_t wakeup_sec, gpio_num_t wakeup_gpio) {
// time stamp sleep start time and save system monotonic time. Deep sleep. // time stamp sleep start time and save system monotonic time. Deep sleep.
gettimeofday(&RTC_sleep_start_time, NULL); gettimeofday(&RTC_sleep_start_time, NULL);
RTC_millis += millis(); RTC_millis += millis();
RTC_time = now();
ESP_LOGI(TAG, "Going to sleep, good bye."); ESP_LOGI(TAG, "Going to sleep, good bye.");
esp_deep_sleep_start(); esp_deep_sleep_start();
} }

View File

@ -43,7 +43,11 @@ void sdcardWriteData(uint16_t noWifi, uint16_t noBle,
__attribute__((unused)) uint16_t noBleCWA) { __attribute__((unused)) uint16_t noBleCWA) {
static int counterWrites = 0; static int counterWrites = 0;
char tempBuffer[12 + 1]; char tempBuffer[12 + 1];
time_t t = now(); time_t t = time(NULL);
struct tm tt;
localtime_r(&t, &tt);
mktime(&tt);
#if (HAS_SDS011) #if (HAS_SDS011)
sdsStatus_t sds; sdsStatus_t sds;
#endif #endif
@ -52,9 +56,9 @@ void sdcardWriteData(uint16_t noWifi, uint16_t noBle,
return; return;
ESP_LOGD(TAG, "writing to SD-card"); ESP_LOGD(TAG, "writing to SD-card");
sprintf(tempBuffer, "%02d.%02d.%4d,", day(t), month(t), year(t)); strftime(tempBuffer, sizeof(tempBuffer), "%d.%m.%Y", &tt);
fileSDCard.print(tempBuffer); fileSDCard.print(tempBuffer);
sprintf(tempBuffer, "%02d:%02d:%02d,", hour(t), minute(t), second(t)); strftime(tempBuffer, sizeof(tempBuffer), "%H.%M.%S", &tt);
fileSDCard.print(tempBuffer); fileSDCard.print(tempBuffer);
sprintf(tempBuffer, "%d,%d", noWifi, noBle); sprintf(tempBuffer, "%d,%d", noWifi, noBle);
fileSDCard.print(tempBuffer); fileSDCard.print(tempBuffer);

View File

@ -8,37 +8,39 @@
#endif #endif
#endif #endif
#define _COMPILETIME compileTime() #if (defined HAS_DCF77 && defined HAS_IF482)
#error You must define at most one of IF482 or DCF77!
#endif
// Local logging tag // Local logging tag
static const char TAG[] = __FILE__; static const char TAG[] = __FILE__;
// symbol to display current time source // symbol to display current time source
// G = GPS / R = RTC / L = LORA / ? = unsynced / <blank> = sync unknown // G = GPS / R = RTC / L = LORA / * = no sync / ? = never synced
const char timeSetSymbols[] = {'G', 'R', 'L', '?', ' '}; const char timeSetSymbols[] = {'G', 'R', 'L', '*', '?'};
// set Time Zone
Timezone myTZ;
bool volatile TimePulseTick = false; bool volatile TimePulseTick = false;
timesource_t timeSource = _unsynced; timesource_t timeSource = _unsynced;
time_t _COMPILETIME = compileTime(__DATE__);
TaskHandle_t ClockTask = NULL; TaskHandle_t ClockTask = NULL;
hw_timer_t *ppsIRQ = NULL; hw_timer_t *ppsIRQ = NULL;
#ifdef HAS_IF482 #ifdef HAS_IF482
HardwareSerial IF482(2); // use UART #2 (#1 may be in use for serial GPS)
static TickType_t txDelay = pdMS_TO_TICKS(1000 - IF482_SYNC_FIXUP) -
tx_Ticks(IF482_FRAME_SIZE, HAS_IF482);
#if (HAS_SDS011) #if (HAS_SDS011)
#error cannot use IF482 together with SDS011 (both use UART#2) #error cannot use IF482 together with SDS011 (both use UART#2)
#endif #endif
HardwareSerial IF482(2); // use UART #2 (#1 may be in use for serial GPS)
#endif #endif // HAS_IF482
Ticker timesyncer; Ticker timesyncer;
void setTimeSyncIRQ() { xTaskNotify(irqHandlerTask, TIMESYNC_IRQ, eSetBits); } void setTimeSyncIRQ() { xTaskNotify(irqHandlerTask, TIMESYNC_IRQ, eSetBits); }
void calibrateTime(void) { void calibrateTime(void) {
ESP_LOGD(TAG, "[%0.3f] calibrateTime, timeSource == %d", millis() / 1000.0, ESP_LOGD(TAG, "[%0.3f] calibrateTime, timeSource == %d", _seconds(),
timeSource); timeSource);
time_t t = 0; time_t t = 0;
uint16_t t_msec = 0; uint16_t t_msec = 0;
@ -76,15 +78,17 @@ void calibrateTime(void) {
} // calibrateTime() } // calibrateTime()
// adjust system time, calibrate RTC and RTC_INT pps // set system time (UTC), calibrate RTC and RTC_INT pps
void IRAM_ATTR setMyTime(uint32_t t_sec, uint16_t t_msec, void IRAM_ATTR setMyTime(uint32_t t_sec, uint16_t t_msec,
timesource_t mytimesource) { timesource_t mytimesource) {
struct timeval tv = {0};
// called with invalid timesource? // called with invalid timesource?
if (mytimesource == _unsynced) if (mytimesource == _unsynced)
return; return;
// increment t_sec only if t_msec > 1000 // increment t_sec if t_msec > 1000
time_t time_to_set = (time_t)(t_sec + t_msec / 1000); time_t time_to_set = (time_t)(t_sec + t_msec / 1000);
// do we have a valid time? // do we have a valid time?
@ -97,8 +101,18 @@ void IRAM_ATTR setMyTime(uint32_t t_sec, uint16_t t_msec,
vTaskDelay(pdMS_TO_TICKS(1000 - t_msec % 1000)); vTaskDelay(pdMS_TO_TICKS(1000 - t_msec % 1000));
} }
ESP_LOGI(TAG, "[%0.3f] UTC time: %d.%03d sec", _seconds(), time_to_set, tv.tv_sec = time_to_set;
t_msec % 1000); tv.tv_usec = 0;
sntp_sync_time(&tv);
ESP_LOGI(TAG, "[%0.3f] UTC time: %d.000 sec", _seconds(), time_to_set);
// if we have a software pps timer, shift it to top of second
if (ppsIRQ != NULL) {
timerWrite(ppsIRQ, 0); // reset pps timer
CLOCKIRQ(); // fire clock pps, this advances time 1 sec
}
// if we have got an external timesource, set RTC time and shift RTC_INT pulse // if we have got an external timesource, set RTC time and shift RTC_INT pulse
// to top of second // to top of second
@ -107,15 +121,8 @@ void IRAM_ATTR setMyTime(uint32_t t_sec, uint16_t t_msec,
set_rtctime(time_to_set); set_rtctime(time_to_set);
#endif #endif
// if we have a software pps timer, shift it to top of second
if (ppsIRQ != NULL) {
timerWrite(ppsIRQ, 0); // reset pps timer
CLOCKIRQ(); // fire clock pps, this advances time 1 sec
}
UTC.setTime(time_to_set); // set the time on top of second
timeSource = mytimesource; // set global variable timeSource = mytimesource; // set global variable
timesyncer.attach(TIME_SYNC_INTERVAL * 60, setTimeSyncIRQ); timesyncer.attach(TIME_SYNC_INTERVAL * 60, setTimeSyncIRQ);
ESP_LOGD(TAG, "[%0.3f] Timesync finished, time was set | timesource=%d", ESP_LOGD(TAG, "[%0.3f] Timesync finished, time was set | timesource=%d",
_seconds(), mytimesource); _seconds(), mytimesource);
@ -132,6 +139,10 @@ void IRAM_ATTR setMyTime(uint32_t t_sec, uint16_t t_msec,
// helper function to setup a pulse per second for time synchronisation // helper function to setup a pulse per second for time synchronisation
uint8_t timepulse_init() { uint8_t timepulse_init() {
// set esp-idf API sntp sync mode
//sntp_init();
sntp_set_sync_mode(SNTP_SYNC_MODE_IMMED);
// use time pulse from GPS as time base with fixed 1Hz frequency // use time pulse from GPS as time base with fixed 1Hz frequency
#ifdef GPS_INT #ifdef GPS_INT
@ -192,11 +203,9 @@ void IRAM_ATTR CLOCKIRQ(void) {
BaseType_t xHigherPriorityTaskWoken = pdFALSE; BaseType_t xHigherPriorityTaskWoken = pdFALSE;
// syncToPPS(); // currently not used
// advance wall clock, if we have // advance wall clock, if we have
#if (defined HAS_IF482 || defined HAS_DCF77) #if (defined HAS_IF482 || defined HAS_DCF77)
xTaskNotifyFromISR(ClockTask, uint32_t(now()), eSetBits, xTaskNotifyFromISR(ClockTask, uint32_t(time(NULL)), eSetBits,
&xHigherPriorityTaskWoken); &xHigherPriorityTaskWoken);
#endif #endif
@ -213,9 +222,9 @@ void IRAM_ATTR CLOCKIRQ(void) {
} }
// helper function to check plausibility of a given epoch time // helper function to check plausibility of a given epoch time
time_t timeIsValid(time_t const t) { bool timeIsValid(time_t const t) {
// is it a time in the past? we use compile date to guess // is t a time in the past? we use compile time to guess
return (t < myTZ.tzTime(_COMPILETIME) ? 0 : t); return (t > _COMPILETIME);
} }
// helper function to calculate serial transmit time // helper function to calculate serial transmit time
@ -230,12 +239,6 @@ TickType_t tx_Ticks(uint32_t framesize, unsigned long baud, uint32_t config,
return round(txTime); return round(txTime);
} }
#if (defined HAS_IF482 || defined HAS_DCF77)
#if (defined HAS_DCF77 && defined HAS_IF482)
#error You must define at most one of IF482 or DCF77!
#endif
void clock_init(void) { void clock_init(void) {
// setup clock output interface // setup clock output interface
@ -245,73 +248,80 @@ void clock_init(void) {
pinMode(HAS_DCF77, OUTPUT); pinMode(HAS_DCF77, OUTPUT);
#endif #endif
time_t userUTCTime = now(); xTaskCreatePinnedToCore(clock_loop, // task function
"clockloop", // name of task
xTaskCreatePinnedToCore(clock_loop, // task function 3072, // stack size of task
"clockloop", // name of task (void *)1, // task parameter
2048, // stack size of task 4, // priority of the task
(void *)&userUTCTime, // start time as task parameter &ClockTask, // task handle
4, // priority of the task 1); // CPU core
&ClockTask, // task handle
1); // CPU core
_ASSERT(ClockTask != NULL); // has clock task started? _ASSERT(ClockTask != NULL); // has clock task started?
} // clock_init } // clock_init
void clock_loop(void *taskparameter) { // ClockTask void clock_loop(void *taskparameter) { // ClockTask
// caveat: don't use now() in this task, it will cause a race condition uint64_t ClockPulse = 0;
// due to concurrent access to i2c bus when reading/writing from/to rtc chip! uint32_t current_time = 0, previous_time = 0;
int8_t ClockMinute = -1;
#define nextmin(t) (t + DCF77_FRAME_SIZE + 1) // next minute time_t tt;
struct tm t = {0};
#ifdef HAS_TWO_LED #ifdef HAS_TWO_LED
static bool led1_state = false; static bool led1_state = false;
#endif #endif
uint32_t printtime;
time_t t = *((time_t *)taskparameter), last_printtime = 0; // UTC time seconds
#ifdef HAS_DCF77
uint8_t *DCFpulse; // pointer on array with DCF pulse bits
DCFpulse = DCF77_Frame(nextmin(t)); // load first DCF frame before start
#elif defined HAS_IF482
static TickType_t txDelay = pdMS_TO_TICKS(1000 - IF482_SYNC_FIXUP) -
tx_Ticks(IF482_FRAME_SIZE, HAS_IF482);
#endif
// output the next second's pulse/telegram after pps arrived // output the next second's pulse/telegram after pps arrived
for (;;) { for (;;) {
// wait for timepulse and store UTC time in seconds got // wait for timepulse and store UTC time
xTaskNotifyWait(0x00, ULONG_MAX, &printtime, portMAX_DELAY); xTaskNotifyWait(0x00, ULONG_MAX, &current_time, portMAX_DELAY);
t = time_t(printtime);
// no confident or no recent time -> suppress clock output if ((sntp_get_sync_status() == SNTP_SYNC_STATUS_IN_PROGRESS) ||
if ((timeStatus() == timeNotSet) || !(timeIsValid(t)) || !(timeIsValid(current_time)) || (current_time == previous_time))
(t == last_printtime))
continue; continue;
// set calendar time for next second of clock output
tt = (time_t)(current_time + 1);
localtime_r(&tt, &t);
mktime(&t);
#if defined HAS_IF482 #if defined HAS_IF482
// wait until moment to fire. Normally we won't get notified during this // wait until moment to fire. Normally we won't get notified during this
// timespan, except when next pps pulse arrives while waiting, because pps // timespan, except when next pps pulse arrives while waiting, because pps
// was adjusted by recent time sync // was adjusted by recent time sync, then advance next_time one second
if (xTaskNotifyWait(0x00, ULONG_MAX, &printtime, txDelay) == pdTRUE) if (xTaskNotifyWait(0x00, ULONG_MAX, &current_time, txDelay) == pdTRUE) {
t = time_t(printtime); // new adjusted UTC time seconds tt = (time_t)(current_time + 1);
localtime_r(&tt, &t);
mktime(&t);
}
// send IF482 telegram // send IF482 telegram
IF482.print(IF482_Frame(t + 2)); // note: telegram is for *next* second IF482.print(IF482_Frame(t)); // note: telegram is for *next* second
ESP_LOGD(TAG, "[%0.3f] IF482: %s", _seconds(), IF482_Frame(t));
#elif defined HAS_DCF77 #elif defined HAS_DCF77
if (second(t) == DCF77_FRAME_SIZE - 1) // is it time to load new frame? // load new frame if second 59 is reached
DCFpulse = DCF77_Frame(nextmin(t)); // generate frame for next minute if (t.tm_sec == 0) {
ClockMinute = t.tm_min;
t.tm_min++; // follow-up minute
mktime(&t); // normalize calendar time
ClockPulse = DCF77_Frame(t); // generate pulse frame
if (minute(nextmin(t)) == // do we still have a recent frame? /* to do here: leap second handling in second 59 */
DCFpulse[DCF77_FRAME_SIZE]) // (timepulses could be missed!)
DCF77_Pulse(t + 1, DCFpulse); // then output next second's pulse
// else we have no recent frame, thus suppressing clock output ESP_LOGD(TAG, "[%0.3f] DCF77: new frame for min %d", _seconds(),
t.tm_min);
} else {
// generate impulse
if (t.tm_min == ClockMinute) { // ensure frame is recent
DCF77_Pulse(ClockPulse & 1); // output next second
ClockPulse >>= 1;
}
}
#endif #endif
@ -324,9 +334,66 @@ void clock_loop(void *taskparameter) { // ClockTask
led1_state = !led1_state; led1_state = !led1_state;
#endif #endif
last_printtime = t; previous_time = current_time;
} // for } // for
} // clock_loop() } // clock_loop()
#endif // HAS_IF482 || defined HAS_DCF77 // we use compile date to create a time_t reference "in the past"
time_t compileTime(const String compile_date) {
char s_month[5];
int year;
struct tm t = {0};
static const char month_names[] = "JanFebMarAprMayJunJulAugSepOctNovDec";
// store compile time once it's calculated
static time_t secs = -1;
if (secs == -1) {
// determine date
// we go one day back to bypass unknown timezone of local time
sscanf(compile_date.c_str(), "%s %d %d", s_month, &t.tm_mday - 1, &year);
t.tm_mon = (strstr(month_names, s_month) - month_names) / 3;
t.tm_year = year - 1900;
// convert to secs local time
secs = mktime(&t);
}
return secs;
}
static bool IsLeapYear(short year) {
if (year % 4 != 0)
return false;
if (year % 100 != 0)
return true;
return (year % 400) == 0;
}
// convert UTC tm time to time_t epoch time
time_t mkgmtime(const struct tm *ptm) {
const int SecondsPerMinute = 60;
const int SecondsPerHour = 3600;
const int SecondsPerDay = 86400;
const int DaysOfMonth[12] = {31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31};
time_t secs = 0;
// tm_year is years since 1900
int year = ptm->tm_year + 1900;
for (int y = 1970; y < year; ++y) {
secs += (IsLeapYear(y) ? 366 : 365) * SecondsPerDay;
}
// tm_mon is month from 0..11
for (int m = 0; m < ptm->tm_mon; ++m) {
secs += DaysOfMonth[m] * SecondsPerDay;
if (m == 1 && IsLeapYear(year))
secs += SecondsPerDay;
}
secs += (ptm->tm_mday - 1) * SecondsPerDay;
secs += ptm->tm_hour * SecondsPerHour;
secs += ptm->tm_min * SecondsPerMinute;
secs += ptm->tm_sec;
return secs;
}

View File

@ -130,7 +130,7 @@ void IRAM_ATTR timesync_processReq(void *taskparameter) {
// calculate average time offset over the summed up difference // calculate average time offset over the summed up difference
time_offset_ms /= TIME_SYNC_SAMPLES; time_offset_ms /= TIME_SYNC_SAMPLES;
// add milliseconds from latest gateway time, and apply a compensation // add milliseconds from latest gateway time, and apply a compensation
// constant for processing times on node and gateway, strip full seconds // constant for processing times on node and gateway, strip full seconds
time_offset_ms += timesync_timestamp[sample_idx - 1][gwtime_msec]; time_offset_ms += timesync_timestamp[sample_idx - 1][gwtime_msec];
@ -142,9 +142,6 @@ void IRAM_ATTR timesync_processReq(void *taskparameter) {
time_offset_sec = timesync_timestamp[sample_idx - 1][gwtime_sec]; time_offset_sec = timesync_timestamp[sample_idx - 1][gwtime_sec];
time_offset_sec += time_offset_ms / 1000; time_offset_sec += time_offset_ms / 1000;
ESP_LOGD(TAG, "LORA date/time: %s",
myTZ.dateTime(time_offset_sec, "d.M Y H:i:s.v T").c_str());
setMyTime(time_offset_sec, time_offset_ms, _lora); 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