Merge branch 'development' into master

This commit is contained in:
Verkehrsrot 2019-03-02 13:37:50 +01:00 committed by GitHub
commit 6b667b4123
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
41 changed files with 630 additions and 629 deletions

View File

@ -235,7 +235,11 @@ Hereafter described is the default *plain* format, which uses MSB bit numbering.
**Port #8:** Battery voltage data (only if device has feature BATT) **Port #8:** Battery voltage data (only if device has feature BATT)
byte 1-2: Battery or USB Voltage [mV], 0 if no battery probe bytes 1-2: Battery or USB Voltage [mV], 0 if no battery probe
**Port #9:** Time/Date
bytes 1-4: board's local time/date in UNIX epoch (number of seconds that have elapsed since January 1, 1970 (midnight UTC/GMT), not counting leap seconds)
# Remote control # Remote control
@ -358,6 +362,10 @@ Note: all settings are stored in NVRAM and will be reloaded when device starts.
Device answers with BME680 sensor data set on Port 7. Device answers with BME680 sensor data set on Port 7.
0x86 get time/date
Device answers with it's local time/date (UTC Unix epoch) on Port 9.
# License # License

View File

@ -1,15 +0,0 @@
#ifndef _CLOCKCONTROLLER_H
#define _CLOCKCONTROLLER_H
#include "globals.h"
#ifdef HAS_IF482
#include "if482.h"
#elif defined HAS_DCF77
#include "dcf77.h"
#endif
void clock_init(void);
void clock_loop(void *pvParameters);
#endif // _CLOCKCONTROLLER_H

View File

@ -5,15 +5,12 @@
#include "senddata.h" #include "senddata.h"
#include "rcommand.h" #include "rcommand.h"
#include "spislave.h" #include "spislave.h"
#include "rtctime.h"
#include <lmic.h> #include <lmic.h>
#ifdef HAS_BME #ifdef HAS_BME
#include "bme680mems.h" #include "bme680mems.h"
#endif #endif
void doHousekeeping(void); void doHousekeeping(void);
uint64_t uptime(void); uint64_t uptime(void);
void reset_counters(void); void reset_counters(void);

View File

@ -6,14 +6,18 @@
#define DCF77_FRAME_SIZE (60) #define DCF77_FRAME_SIZE (60)
#define DCF77_PULSE_LENGTH (100) #define DCF77_PULSE_LENGTH (100)
extern uint8_t DCFpulse[]; #ifdef DCF77_ACTIVE_LOW
enum dcf_pinstate { dcf_high, dcf_low };
enum dcf_pulses { dcf_off, dcf_zero, dcf_one }; #else
enum dcf_pinstate { dcf_low, dcf_high }; enum dcf_pinstate { dcf_low, dcf_high };
#endif
void DCF_Pulse(time_t t); enum DCF77_Pulses { dcf_Z, dcf_0, dcf_1 };
void IRAM_ATTR DCF77_Frame(time_t t);
void set_DCF77_pin(dcf_pinstate state); void DCF77_Pulse(time_t t, uint8_t const *DCFpulse);
uint8_t dec2bcd(uint8_t dec, uint8_t startpos, uint8_t endpos, uint8_t pArray[]); 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

@ -3,9 +3,9 @@
#include <U8x8lib.h> #include <U8x8lib.h>
#include "cyclic.h" #include "cyclic.h"
#include "rtctime.h"
extern uint8_t volatile DisplayState; extern uint8_t DisplayState;
extern HAS_DISPLAY u8x8; extern HAS_DISPLAY u8x8;
void init_display(const char *Productname, const char *Version); void init_display(const char *Productname, const char *Version);

View File

@ -7,6 +7,7 @@
// Time functions // Time functions
#include <Time.h> #include <Time.h>
#include <Timezone.h> #include <Timezone.h>
#include <RtcDateTime.h>
// std::set for unified array functions // std::set for unified array functions
#include <set> #include <set>
@ -96,6 +97,7 @@ typedef struct {
} bmeStatus_t; } bmeStatus_t;
enum sendprio_t { prio_low, prio_normal, prio_high }; enum sendprio_t { prio_low, prio_normal, prio_high };
enum timesource_t { _gps, _rtc, _lora, _unsynced };
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;
@ -106,12 +108,14 @@ extern char display_line6[], display_line7[]; // screen buffers
extern uint8_t volatile channel; // wifi channel rotation counter extern uint8_t volatile channel; // wifi channel rotation counter
extern uint16_t volatile macs_total, macs_wifi, macs_ble, extern uint16_t volatile macs_total, macs_wifi, macs_ble,
batt_voltage; // display values batt_voltage; // display values
extern bool volatile TimePulseTick; extern bool volatile TimePulseTick; // 1sec pps flag set by GPS or RTC
extern hw_timer_t *sendCycle, *displaytimer; extern timesource_t timeSource;
extern hw_timer_t *sendCycle, *displaytimer, *clockCycle;
extern SemaphoreHandle_t I2Caccess, TimePulse; extern SemaphoreHandle_t I2Caccess, TimePulse;
extern TaskHandle_t irqHandlerTask, ClockTask; extern TaskHandle_t irqHandlerTask, ClockTask;
extern TimerHandle_t WifiChanTimer; extern TimerHandle_t WifiChanTimer;
extern Timezone myTZ; extern Timezone myTZ;
extern time_t userUTCTime;
// application includes // application includes
#include "led.h" #include "led.h"

View File

@ -2,15 +2,21 @@
#define _GPSREAD_H #define _GPSREAD_H
#include <TinyGPS++.h> // library for parsing NMEA data #include <TinyGPS++.h> // library for parsing NMEA data
#include <RtcDateTime.h>
#include "timekeeper.h"
#ifdef GPS_I2C // Needed for reading from I2C Bus #ifdef GPS_I2C // Needed for reading from I2C Bus
#include <Wire.h> #include <Wire.h>
#endif #endif
#define NMEA_FRAME_SIZE 80 // NEMA has a maxium of 80 bytes per record
#define NMEA_BUFFERTIME 50 // 50ms safety time regardless
extern TinyGPSPlus gps; // Make TinyGPS++ instance globally availabe extern TinyGPSPlus gps; // Make TinyGPS++ instance globally availabe
extern gpsStatus_t extern gpsStatus_t
gps_status; // Make struct for storing gps data globally available gps_status; // Make struct for storing gps data globally available
extern TaskHandle_t GpsTask; extern TaskHandle_t GpsTask;
extern TickType_t const gpsDelay_ticks; // time to NMEA arrival
int gps_init(void); int gps_init(void);
void gps_read(void); void gps_read(void);

View File

@ -2,6 +2,7 @@
#define _IF482_H #define _IF482_H
#include "globals.h" #include "globals.h"
#include "timekeeper.h"
#define IF482_FRAME_SIZE (17) #define IF482_FRAME_SIZE (17)
#define IF482_PULSE_LENGTH (1000) #define IF482_PULSE_LENGTH (1000)
@ -10,7 +11,5 @@ extern HardwareSerial IF482;
void IF482_Pulse(time_t t); void IF482_Pulse(time_t t);
String IRAM_ATTR IF482_Frame(time_t tt); String IRAM_ATTR IF482_Frame(time_t tt);
TickType_t tx_Ticks(unsigned long baud, uint32_t config, int8_t rxPin,
int8_t txPins);
#endif #endif

View File

@ -9,6 +9,7 @@
#include "globals.h" #include "globals.h"
#include "cyclic.h" #include "cyclic.h"
#include "senddata.h" #include "senddata.h"
#include "timekeeper.h"
void irqHandler(void *pvParameters); void irqHandler(void *pvParameters);
void IRAM_ATTR homeCycleIRQ(); void IRAM_ATTR homeCycleIRQ();

View File

@ -3,6 +3,7 @@
#include "globals.h" #include "globals.h"
#include "rcommand.h" #include "rcommand.h"
#include "timekeeper.h"
// LMIC-Arduino LoRaWAN Stack // LMIC-Arduino LoRaWAN Stack
#include <lmic.h> #include <lmic.h>
@ -10,17 +11,15 @@
#include <SPI.h> #include <SPI.h>
#include <arduino_lmic_hal_boards.h> #include <arduino_lmic_hal_boards.h>
#include "loraconf.h" #include "loraconf.h"
#include "rtctime.h"
// Needed for 24AA02E64, does not hurt anything if included and not used // Needed for 24AA02E64, does not hurt anything if included and not used
#ifdef MCP_24AA02E64_I2C_ADDRESS #ifdef MCP_24AA02E64_I2C_ADDRESS
#include <Wire.h> #include <Wire.h>
#endif #endif
extern QueueHandle_t LoraSendQueue; extern QueueHandle_t LoraSendQueue;
esp_err_t lora_stack_init();
void onEvent(ev_t ev); void onEvent(ev_t ev);
void gen_lora_deveui(uint8_t *pdeveui); void gen_lora_deveui(uint8_t *pdeveui);
void RevBytes(unsigned char *b, size_t c); void RevBytes(unsigned char *b, size_t c);
@ -36,7 +35,4 @@ void lora_queuereset(void);
void lora_housekeeping(void); void lora_housekeeping(void);
void user_request_network_time_callback(void *pVoidUserUTCTime, void user_request_network_time_callback(void *pVoidUserUTCTime,
int flagSuccess); int flagSuccess);
esp_err_t lora_stack_init();
#endif #endif

View File

@ -17,6 +17,5 @@
#include "led.h" #include "led.h"
#include "spislave.h" #include "spislave.h"
#include "lorawan.h" #include "lorawan.h"
#include "rtctime.h" #include "timekeeper.h"
#include "clockcontroller.h"
#endif #endif

View File

@ -1,7 +1,8 @@
#ifndef _PAYLOAD_H_ #ifndef _PAYLOAD_H_
#define _PAYLOAD_H_ #define _PAYLOAD_H_
// MyDevices CayenneLPP channels for dynamic sensor payload format // MyDevices CayenneLPP 1.0 channels for Synamic sensor payload format
// all payload goes out on LoRa FPort 1
#if (PAYLOAD_ENCODER == 3) #if (PAYLOAD_ENCODER == 3)
#define LPP_GPS_CHANNEL 20 #define LPP_GPS_CHANNEL 20
@ -19,7 +20,7 @@
#endif #endif
// MyDevices CayenneLPP types // MyDevices CayenneLPP 2.0 types for Packed Sensor Payload, not using channels, but different FPorts
#define LPP_GPS 136 // 3 byte lon/lat 0.0001 °, 3 bytes alt 0.01m #define LPP_GPS 136 // 3 byte lon/lat 0.0001 °, 3 bytes alt 0.01m
#define LPP_TEMPERATURE 103 // 2 bytes, 0.1°C signed MSB #define LPP_TEMPERATURE 103 // 2 bytes, 0.1°C signed MSB
#define LPP_DIGITAL_INPUT 0 // 1 byte #define LPP_DIGITAL_INPUT 0 // 1 byte
@ -49,6 +50,7 @@ public:
void addBME(bmeStatus_t value); void addBME(bmeStatus_t value);
void addButton(uint8_t value); void addButton(uint8_t value);
void addSensor(uint8_t[]); void addSensor(uint8_t[]);
void addTime(time_t value);
#if PAYLOAD_ENCODER == 1 // format plain #if PAYLOAD_ENCODER == 1 // format plain

View File

@ -2,27 +2,16 @@
#define _RTCTIME_H #define _RTCTIME_H
#include "globals.h" #include "globals.h"
#include "timekeeper.h"
#include <Wire.h> // must be included here so that Arduino library object file references work #include <Wire.h> // must be included here so that Arduino library object file references work
#include <RtcDS3231.h> #include <RtcDS3231.h>
#ifdef HAS_GPS
#include "gpsread.h"
#endif
extern RtcDS3231<TwoWire> Rtc; // make RTC instance globally available extern RtcDS3231<TwoWire> Rtc; // make RTC instance globally available
int rtc_init(void); uint8_t rtc_init(void);
int set_rtctime(uint32_t t); uint8_t set_rtctime(time_t t);
int set_rtctime(time_t t);
void sync_rtctime(void); void sync_rtctime(void);
time_t get_rtctime(void); time_t get_rtctime(void);
float get_rtctemp(void); float get_rtctemp(void);
void IRAM_ATTR CLOCKIRQ(void);
int timepulse_init(void);
void timepulse_start(void);
int sync_TimePulse(void);
int sync_SysTime(time_t);
int sync_SysTime(uint32_t t);
time_t best_time(void);
#endif // _RTCTIME_H #endif // _RTCTIME_H

32
include/timekeeper.h Normal file
View File

@ -0,0 +1,32 @@
#ifndef _timekeeper_H
#define _timekeeper_H
#include "globals.h"
#include "rtctime.h"
#include "TimeLib.h"
#ifdef HAS_GPS
#include "gpsread.h"
#endif
#ifdef HAS_IF482
#include "if482.h"
#elif defined HAS_DCF77
#include "dcf77.h"
#endif
extern const char timeSetSymbols[];
void IRAM_ATTR CLOCKIRQ(void);
void clock_init(void);
void clock_loop(void *pvParameters);
void timepulse_start(void);
uint8_t timepulse_init(void);
time_t timeIsValid(time_t const t);
time_t timeProvider(void);
time_t compiledUTC(void);
time_t tmConvert(uint16_t YYYY, uint8_t MM, uint8_t DD, uint8_t hh, uint8_t mm,
uint8_t ss);
TickType_t tx_Ticks(uint32_t framesize, unsigned long baud, uint32_t config,
int8_t rxPin, int8_t txPins);
#endif // _timekeeper_H

1
lib/microTime Submodule

@ -0,0 +1 @@
Subproject commit 6d5b82c554590f49864cc44ce295ec91dcf1114e

View File

@ -6,7 +6,7 @@
; ---> SELECT TARGET PLATFORM HERE! <--- ; ---> SELECT TARGET PLATFORM HERE! <---
[platformio] [platformio]
env_default = generic ;env_default = generic
;env_default = ebox ;env_default = ebox
;env_default = eboxtube ;env_default = eboxtube
;env_default = heltec ;env_default = heltec
@ -16,7 +16,7 @@ env_default = generic
;env_default = ttgov21old ;env_default = ttgov21old
;env_default = ttgov21new ;env_default = ttgov21new
;env_default = ttgobeam ;env_default = ttgobeam
;env_default = ttgofox env_default = ttgofox
;env_default = lopy ;env_default = lopy
;env_default = lopy4 ;env_default = lopy4
;env_default = fipy ;env_default = fipy
@ -30,16 +30,16 @@ description = Paxcounter is a proof-of-concept ESP32 device for metering passeng
[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.7.31 release_version = 1.7.323
; 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 = 0 debug_level = 4
; UPLOAD MODE: select esptool to flash via USB/UART, select custom to upload to cloud for OTA ; UPLOAD MODE: select esptool to flash via USB/UART, select custom to upload to cloud for OTA
upload_protocol = esptool upload_protocol = esptool
;upload_protocol = custom ;upload_protocol = custom
extra_scripts = pre:build.py extra_scripts = pre:build.py
keyfile = ota.conf keyfile = ota.conf
platform_espressif32 = espressif32@1.6.0 platform_espressif32 = espressif32@1.7.0
;platform_espressif32 = https://github.com/platformio/platform-espressif32.git#feature/stage ;platform_espressif32 = https://github.com/platformio/platform-espressif32.git#feature/stage
board_build.partitions = min_spiffs.csv board_build.partitions = min_spiffs.csv
monitor_speed = 115200 monitor_speed = 115200

View File

@ -1,7 +1,7 @@
#include "globals.h" #include "globals.h"
// Local logging tag // Local logging tag
static const char TAG[] = "main"; static const char TAG[] = __FILE__;
#ifdef HAS_BATTERY_PROBE #ifdef HAS_BATTERY_PROBE
esp_adc_cal_characteristics_t *adc_characs = esp_adc_cal_characteristics_t *adc_characs =
@ -48,7 +48,6 @@ uint16_t read_voltage() {
#ifdef BATT_FACTOR #ifdef BATT_FACTOR
voltage *= BATT_FACTOR; voltage *= BATT_FACTOR;
#endif #endif
ESP_LOGD(TAG, "Raw: %d / Voltage: %dmV", adc_reading, voltage);
return voltage; return voltage;
#else #else
return 0; return 0;

View File

@ -3,7 +3,7 @@
#include "bme680mems.h" #include "bme680mems.h"
// Local logging tag // Local logging tag
static const char TAG[] = "main"; static const char TAG[] = __FILE__;
bmeStatus_t bme_status; bmeStatus_t bme_status;
TaskHandle_t BmeTask; TaskHandle_t BmeTask;

View File

@ -4,7 +4,7 @@
#include "button.h" #include "button.h"
// Local logging tag // Local logging tag
static const char TAG[] = "main"; static const char TAG[] = __FILE__;
void readButton() { void readButton() {
ESP_LOGI(TAG, "Button pressed"); ESP_LOGI(TAG, "Button pressed");

View File

@ -1,74 +0,0 @@
#include "clockcontroller.h"
#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
// Local logging tag
static const char TAG[] = "main";
void clock_init(void) {
// setup clock output interface
#ifdef HAS_IF482
IF482.begin(HAS_IF482);
#elif defined HAS_DCF77
pinMode(HAS_DCF77, OUTPUT);
#endif
xTaskCreatePinnedToCore(clock_loop, // task function
"clockloop", // name of task
2048, // stack size of task
(void *)1, // task parameter
4, // priority of the task
&ClockTask, // task handle
0); // CPU core
assert(ClockTask); // has clock task started?
} // clock_init
void clock_loop(void *pvParameters) { // ClockTask
configASSERT(((uint32_t)pvParameters) == 1); // FreeRTOS check
TickType_t wakeTime;
time_t t;
#define t1(t) (t + DCF77_FRAME_SIZE + 1) // future time for next frame
// preload first DCF frame before start
#ifdef HAS_DCF77
DCF77_Frame(t1(best_time()));
#endif
// output time telegram for second following sec beginning with timepulse
for (;;) {
xTaskNotifyWait(0x00, ULONG_MAX, &wakeTime,
portMAX_DELAY); // wait for timepulse
if (timeStatus() == timeNotSet) // do we have valid time?
continue;
t = best_time(); // time to send to clock
#if defined HAS_IF482
IF482_Pulse(t + 1); // next second
#elif defined HAS_DCF77
if (second(t) == DCF77_FRAME_SIZE - 1) // moment to reload frame?
DCF77_Frame(t1(t)); // generate next frame
if (DCFpulse[DCF77_FRAME_SIZE] ==
minute(t1(t))) // do he have a recent frame?
DCF_Pulse(t + 1); // then output next second of current frame
#endif
} // for
} // clock_loop()
#endif // HAS_IF482 || defined HAS_DCF77

View File

@ -5,11 +5,7 @@
#include "cyclic.h" #include "cyclic.h"
// Local logging tag // Local logging tag
static const char TAG[] = "main"; static const char TAG[] = __FILE__;
time_t userUTCTime; // Seconds since the UTC epoch
unsigned long nextLoraTimeSync = millis();
unsigned long nextGPSTimeSync = millis();
// do all housekeeping // do all housekeeping
void doHousekeeping() { void doHousekeeping() {
@ -21,36 +17,11 @@ void doHousekeeping() {
if (cfg.runmode == 1) if (cfg.runmode == 1)
do_reset(); do_reset();
#ifdef HAS_SPI
spi_housekeeping(); spi_housekeeping();
#endif
#ifdef HAS_LORA
lora_housekeeping(); lora_housekeeping();
// do cyclic sync of systime with GPS timepulse, if present
#if defined HAS_GPS && defined TIME_SYNC_INTERVAL_GPS
if (millis() >= nextGPSTimeSync) {
nextGPSTimeSync = millis() + TIME_SYNC_INTERVAL_GPS *
60000; // set up next time sync period
// sync systime on next timepulse
if (sync_SysTime(get_gpstime())) {
//setSyncProvider(get_gpstime);
#ifdef HAS_RTC
set_rtctime(now()); // epoch time
#endif
ESP_LOGI(TAG, "GPS has set the system time");
} else
ESP_LOGI(TAG, "Unable to sync system time with GPS");
} // if
#endif
// do cyclic time sync with LORA network, if present
#if defined HAS_LORA && defined TIME_SYNC_INTERVAL_LORA
if (millis() >= nextLoraTimeSync) {
nextLoraTimeSync = millis() + TIME_SYNC_INTERVAL_LORA *
60000; // set up next time sync period
// Schedule a network time sync request at the next possible time
LMIC_requestNetworkTime(user_request_network_time_callback, &userUTCTime);
ESP_LOGI(TAG, "LORAWAN time request scheduled");
}
#endif #endif
// task storage debugging // // task storage debugging //

View File

@ -14,19 +14,15 @@ https://github.com/udoklein/dcf77
#include "dcf77.h" #include "dcf77.h"
// Local logging tag // Local logging tag
static const char TAG[] = "main"; static const char TAG[] = __FILE__;
// array of dcf pulses for one minute // triggered by second timepulse to ticker out DCF signal
uint8_t DCFpulse[DCF77_FRAME_SIZE + 1]; void DCF77_Pulse(time_t t, uint8_t const *DCFpulse) {
// triggered by 1 second timepulse to ticker out DCF signal
void DCF_Pulse(time_t t) {
uint8_t sec = second(t);
TickType_t startTime = xTaskGetTickCount(); TickType_t startTime = xTaskGetTickCount();
uint8_t sec = second(t);
ESP_LOGD(TAG, "DCF77 sec %d", sec); ESP_LOGD (TAG, "DCF second %d", sec);
// induce 10 pulses // induce 10 pulses
for (uint8_t pulse = 0; pulse <= 9; pulse++) { for (uint8_t pulse = 0; pulse <= 9; pulse++) {
@ -34,91 +30,84 @@ void DCF_Pulse(time_t t) {
switch (pulse) { switch (pulse) {
case 0: // start of second -> start of timeframe for logic signal case 0: // start of second -> start of timeframe for logic signal
if (DCFpulse[sec] != dcf_off) if (DCFpulse[sec] != dcf_Z)
set_DCF77_pin(dcf_low); digitalWrite(HAS_DCF77, dcf_low);
else // 59th second reached, nothing more to do
return;
break; break;
case 1: // 100ms after start of second -> end of timeframe for logic 0 case 1: // 100ms after start of second -> end of timeframe for logic 0
if (DCFpulse[sec] == dcf_zero) if (DCFpulse[sec] == dcf_0)
set_DCF77_pin(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 after start of second -> end of timeframe for logic 1
set_DCF77_pin(dcf_high); digitalWrite(HAS_DCF77, dcf_high);
break; break;
case 9: // 900ms after start -> last pulse case 9: // 900ms after start -> last pulse
return; break;
} // switch } // switch
// pulse pause
vTaskDelayUntil(&startTime, pdMS_TO_TICKS(DCF77_PULSE_LENGTH)); vTaskDelayUntil(&startTime, pdMS_TO_TICKS(DCF77_PULSE_LENGTH));
} // for } // for
} // DCF_Pulse() } // DCF77_Pulse()
void IRAM_ATTR DCF77_Frame(time_t tt) { uint8_t *IRAM_ATTR DCF77_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] = {
dcf_0, dcf_0, dcf_0, dcf_0, dcf_0, dcf_0, dcf_0,
dcf_0, dcf_0, dcf_0, dcf_0, dcf_0, dcf_0, dcf_0,
dcf_0, dcf_0, dcf_0, dcf_0, dcf_0, dcf_0, dcf_1};
uint8_t Parity; uint8_t Parity;
time_t t = myTZ.toLocal(tt); // convert to local time time_t t = myTZ.toLocal(tt); // convert to local time
ESP_LOGD(TAG, "DCF77 minute %d", minute(t)); // ENCODE DST CHANGE ANNOUNCEMENT (Sec 16)
DCFpulse[16] = dcf_0; // not yet implemented
// ENCODE HEAD // ENCODE DAYLIGHTSAVING (secs 17..18)
// secs 0..19 initialized with zeros DCFpulse[17] = myTZ.locIsDST(t) ? dcf_1 : dcf_0;
for (int n = 0; n <= 19; n++) DCFpulse[18] = myTZ.locIsDST(t) ? dcf_0 : dcf_1;
DCFpulse[n] = dcf_zero;
// secs 17..18: adjust for DayLightSaving
DCFpulse[18 - (myTZ.locIsDST(t) ? 1 : 0)] = dcf_one;
// sec 20: must be 1 to indicate time active
DCFpulse[20] = dcf_one;
// ENCODE MINUTE (secs 21..28) // ENCODE MINUTE (secs 21..28)
Parity = dec2bcd(minute(t), 21, 27, DCFpulse); Parity = dec2bcd(minute(t), 21, 27, DCFpulse);
DCFpulse[28] = (Parity & 1) ? dcf_one : dcf_zero; DCFpulse[28] = setParityBit(Parity);
// ENCODE HOUR (secs 29..35) // ENCODE HOUR (secs 29..35)
Parity = dec2bcd(hour(t), 29, 34, DCFpulse); Parity = dec2bcd(hour(t), 29, 34, DCFpulse);
DCFpulse[35] = (Parity & 1) ? dcf_one : dcf_zero; DCFpulse[35] = setParityBit(Parity);
// ENCODE DATE (secs 36..58) // ENCODE DATE (secs 36..58)
Parity = dec2bcd(day(t), 36, 41, DCFpulse); Parity = dec2bcd(day(t), 36, 41, DCFpulse);
Parity += dec2bcd((weekday(t) - 1) ? (weekday(t) - 1) : 7, 42, 44, DCFpulse); Parity += dec2bcd((weekday(t) - 1) ? (weekday(t) - 1) : 7, 42, 44, DCFpulse);
Parity += dec2bcd(month(t), 45, 49, DCFpulse); Parity += dec2bcd(month(t), 45, 49, DCFpulse);
Parity += dec2bcd(year(t) - 2000, 50, 57, Parity += dec2bcd(year(t) - 2000, 50, 57, DCFpulse);
DCFpulse); // yes, we have a millenium 3000 bug here ;-) DCFpulse[58] = setParityBit(Parity);
DCFpulse[58] = (Parity & 1) ? dcf_one : dcf_zero;
// ENCODE TAIL (sec 59) // ENCODE MARK (sec 59)
DCFpulse[59] = dcf_off; DCFpulse[59] = dcf_Z; // !! missing code here for leap second !!
// !! missing code here for leap second !!
// timestamp the frame with minute pointer // timestamp this frame with it's minute
DCFpulse[60] = minute(t); DCFpulse[60] = minute(t);
/* return DCFpulse;
// for debug: print the DCF77 frame buffer
char out[DCF77_FRAME_SIZE + 1]; } // DCF77_Frame()
uint8_t i;
for (i = 0; i < DCF77_FRAME_SIZE; i++) {
out[i] = DCFpulse[i] + '0'; // convert int digit to printable ascii
}
out[DCF77_FRAME_SIZE] = '\0'; // string termination char
ESP_LOGD(TAG, "DCF minute %d = %s", DCFpulse[DCF77_FRAME_SIZE], out);
*/
}
// helper function to convert decimal to bcd digit // helper function to convert decimal to bcd digit
uint8_t IRAM_ATTR dec2bcd(uint8_t dec, uint8_t startpos, uint8_t endpos, uint8_t IRAM_ATTR dec2bcd(uint8_t const dec, uint8_t const startpos, uint8_t const endpos,
uint8_t pArray[]) { uint8_t *DCFpulse) {
uint8_t data = (dec < 10) ? dec : ((dec / 10) << 4) + (dec % 10); uint8_t data = (dec < 10) ? dec : ((dec / 10) << 4) + (dec % 10);
uint8_t parity = 0; uint8_t parity = 0;
for (uint8_t n = startpos; n <= endpos; n++) { for (uint8_t i = startpos; i <= endpos; i++) {
pArray[n] = (data & 1) ? dcf_one : dcf_zero; DCFpulse[i] = (data & 1) ? dcf_1 : dcf_0;
parity += (data & 1); parity += (data & 1);
data >>= 1; data >>= 1;
} }
@ -126,24 +115,7 @@ uint8_t IRAM_ATTR dec2bcd(uint8_t dec, uint8_t startpos, uint8_t endpos,
return parity; return parity;
} }
// helper function to switch GPIO line with DCF77 signal // helper function to encode parity
void set_DCF77_pin(dcf_pinstate state) { uint8_t IRAM_ATTR setParityBit(uint8_t const p) { return ((p & 1) ? dcf_1 : dcf_0); }
switch (state) {
case dcf_low:
#ifdef DCF77_ACTIVE_LOW
digitalWrite(HAS_DCF77, HIGH);
#else
digitalWrite(HAS_DCF77, LOW);
#endif
break;
case dcf_high:
#ifdef DCF77_ACTIVE_LOW
digitalWrite(HAS_DCF77, LOW);
#else
digitalWrite(HAS_DCF77, HIGH);
#endif
break;
} // switch
} // DCF77_pulse
#endif // HAS_DCF77 #endif // HAS_DCF77

View File

@ -41,21 +41,11 @@ const char lora_datarate[] = {"1211100908078CNA1211109C8C7C"};
const char lora_datarate[] = {"121110090807FSNA"}; const char lora_datarate[] = {"121110090807FSNA"};
#endif #endif
// time display symbols
#if defined HAS_GPS || defined HAS_RTC
const char timeNosyncSymbol = '?';
#if defined HAS_IF482
const char timesyncSymbol = '+';
#elif defined HAS_DCF77
const char timesyncSymbol = '*';
#endif
#endif
// helper arry for converting month values to text // helper arry 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"};
uint8_t volatile DisplayState = 0; uint8_t DisplayState = 0;
// helper function, prints a hex key on display // helper function, prints a hex key on display
void DisplayKey(const uint8_t *key, uint8_t len, bool lsb) { void DisplayKey(const uint8_t *key, uint8_t len, bool lsb) {
@ -134,16 +124,14 @@ void init_display(const char *Productname, const char *Version) {
u8x8.printf(!cfg.rssilimit ? "RLIM:off " : "RLIM:%d", cfg.rssilimit); u8x8.printf(!cfg.rssilimit ? "RLIM:off " : "RLIM:%d", cfg.rssilimit);
I2C_MUTEX_UNLOCK(); // release i2c bus access I2C_MUTEX_UNLOCK(); // release i2c bus access
} } // mutex
} // init_display } // init_display
void refreshtheDisplay() { void refreshtheDisplay() {
uint8_t msgWaiting; uint8_t msgWaiting;
char timeSync, timeState; char timeState, buff[16];
char buff[16]; // 16 chars line buffer time_t t = myTZ.toLocal(now()); // note: call now() here *before* locking mutex!
time_t t;
// block i2c bus access // block i2c bus access
if (I2C_MUTEX_LOCK()) { if (I2C_MUTEX_LOCK()) {
@ -155,8 +143,10 @@ void refreshtheDisplay() {
} }
// if display is switched off we don't refresh it to relax cpu // if display is switched off we don't refresh it to relax cpu
if (!DisplayState) if (!DisplayState) {
I2C_MUTEX_UNLOCK(); // release i2c bus access
return; return;
}
// update counter (lines 0-1) // update counter (lines 0-1)
snprintf( snprintf(
@ -225,9 +215,7 @@ void refreshtheDisplay() {
// update LoRa status display (line 6) // update LoRa status display (line 6)
u8x8.printf("%-16s", display_line6); u8x8.printf("%-16s", display_line6);
#else // we want a systime display instead LoRa status #else // we want a systime display instead LoRa status
t = myTZ.toLocal(best_time()); timeState = TimePulseTick ? ' ' : timeSetSymbols[timeSource];
timeSync = (timeStatus() == timeSet) ? timesyncSymbol : timeNosyncSymbol;
timeState = TimePulseTick ? timeSync : ' ';
TimePulseTick = false; TimePulseTick = false;
u8x8.printf("%02d:%02d:%02d%c %2d.%3s", hour(t), minute(t), second(t), u8x8.printf("%02d:%02d:%02d%c %2d.%3s", hour(t), minute(t), second(t),
timeState, day(t), printmonth[month(t)]); timeState, day(t), printmonth[month(t)]);
@ -249,8 +237,7 @@ void refreshtheDisplay() {
#endif // HAS_LORA #endif // HAS_LORA
I2C_MUTEX_UNLOCK(); // release i2c bus access I2C_MUTEX_UNLOCK(); // release i2c bus access
} } // mutex
} // refreshDisplay() } // refreshDisplay()
#endif // HAS_DISPLAY #endif // HAS_DISPLAY

View File

@ -3,7 +3,7 @@
#include "globals.h" #include "globals.h"
// Local logging tag // Local logging tag
static const char TAG[] = "main"; static const char TAG[] = __FILE__;
TinyGPSPlus gps; TinyGPSPlus gps;
gpsStatus_t gps_status; gpsStatus_t gps_status;
@ -11,6 +11,10 @@ TaskHandle_t GpsTask;
#ifdef GPS_SERIAL #ifdef GPS_SERIAL
HardwareSerial GPS_Serial(1); // use UART #1 HardwareSerial GPS_Serial(1); // use UART #1
TickType_t const gpsDelay_ticks = pdMS_TO_TICKS(1000 - NMEA_BUFFERTIME) -
tx_Ticks(NMEA_FRAME_SIZE, GPS_SERIAL);
#else
TickType_t const gpsDelay_ticks = pdMS_TO_TICKS(1000 - NMEA_BUFFERTIME);
#endif #endif
// initialize and configure GPS // initialize and configure GPS
@ -23,6 +27,13 @@ int gps_init(void) {
return 0; return 0;
} }
// set timeout for reading recent time from GPS
#ifdef GPS_SERIAL // serial GPS
#else // I2C GPS
#endif
#if defined GPS_SERIAL #if defined GPS_SERIAL
GPS_Serial.begin(GPS_SERIAL); GPS_Serial.begin(GPS_SERIAL);
ESP_LOGI(TAG, "Using serial GPS"); ESP_LOGI(TAG, "Using serial GPS");
@ -73,32 +84,23 @@ void gps_read() {
gps.passedChecksum(), gps.failedChecksum(), gps.sentencesWithFix()); gps.passedChecksum(), gps.failedChecksum(), gps.sentencesWithFix());
} }
// helper function to convert gps date/time into time_t
time_t tmConvert_t(uint16_t YYYY, uint8_t MM, uint8_t DD, uint8_t hh,
uint8_t mm, uint8_t ss) {
tmElements_t tm;
tm.Year = YYYY - 1970; // note year argument is offset from 1970 in time.h
tm.Month = MM;
tm.Day = DD;
tm.Hour = hh;
tm.Minute = mm;
tm.Second = ss;
return makeTime(tm);
}
// function to fetch current time from gps // function to fetch current time from gps
time_t get_gpstime(void) { time_t get_gpstime(void) {
// !! never call now() or delay in this function, this would break this
// function to be used as SyncProvider for Time.h
time_t t = 0; // 0 effects calling SyncProvider() to not set time // set time to wait for arrive next recent NMEA time record
static const uint32_t gpsDelay_ms = gpsDelay_ticks / portTICK_PERIOD_MS;
if ((gps.time.age() < 1500) && (gps.time.isValid())) { time_t t = 0;
// get current gps time
t = tmConvert_t(gps.date.year(), gps.date.month(), gps.date.day(), if ((gps.time.age() < gpsDelay_ms) && (gps.time.isValid()) && (gps.date.isValid())) {
ESP_LOGD(TAG, "GPS time age: %dms, second: %d, is valid: %s", gps.time.age(), gps.time.second(),
gps.time.isValid() ? "yes" : "no");
t = tmConvert(gps.date.year(), gps.date.month(), gps.date.day(),
gps.time.hour(), gps.time.minute(), gps.time.second()); gps.time.hour(), gps.time.minute(), gps.time.second());
} }
return t; return timeIsValid(t);
} // get_gpstime() } // get_gpstime()
// GPS serial feed FreeRTos Task // GPS serial feed FreeRTos Task

View File

@ -25,20 +25,24 @@
#define GPS_SERIAL 9600, SERIAL_8N1, GPIO_NUM_12, GPIO_NUM_15 // UBlox NEO 6M #define GPS_SERIAL 9600, SERIAL_8N1, GPIO_NUM_12, GPIO_NUM_15 // UBlox NEO 6M
//#define GPS_INT GPIO_NUM_34 // 30ns accurary timepulse, to be external wired on pcb: NEO 6M Pin#3 -> GPIO34 //#define GPS_INT GPIO_NUM_34 // 30ns accurary timepulse, to be external wired on pcb: NEO 6M Pin#3 -> GPIO34
// Settings for on board DS3231 RTC chip
//#define HAS_RTC MY_OLED_SDA, MY_OLED_SCL // SDA, SCL
//#define RTC_INT GPIO_NUM_13 // timepulse with accuracy +/- 2*e-6 [microseconds] = 0,1728sec / day
// enable only if device has these sensors, otherwise comment these lines // enable only if device has these sensors, otherwise comment these lines
// BME680 sensor on I2C bus // BME680 sensor on I2C bus
//#define HAS_BME SDA, SCL #define HAS_BME SDA, SCL
//#define BME_ADDR BME680_I2C_ADDR_PRIMARY // !! connect SDIO of BME680 to GND !! #define BME_ADDR BME680_I2C_ADDR_PRIMARY // !! connect SDIO of BME680 to GND !!
// display (if connected) // display (if connected)
//#define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C #define HAS_DISPLAY U8X8_SSD1306_128X64_NONAME_HW_I2C
//#define MY_OLED_SDA SDA #define MY_OLED_SDA SDA
//#define MY_OLED_SCL SCL #define MY_OLED_SCL SCL
//#define MY_OLED_RST U8X8_PIN_NONE #define MY_OLED_RST U8X8_PIN_NONE
//#define DISPLAY_FLIP 1 // use if display is rotated //#define DISPLAY_FLIP 1 // use if display is rotated
// Settings for DCF77 interface // Settings for DCF77 interface
//#define HAS_DCF77 GPIO_NUM_13 #define HAS_DCF77 GPIO_NUM_13
// Settings for IF482 interface // Settings for IF482 interface
//#define HAS_IF482 9600, SERIAL_7E1, GPIO_NUM_12, GPIO_NUM_14 // IF482 serial port parameters //#define HAS_IF482 9600, SERIAL_7E1, GPIO_NUM_12, GPIO_NUM_14 // IF482 serial port parameters

View File

@ -28,12 +28,13 @@
//#define HAS_IF482 9600, SERIAL_7E1, GPIO_NUM_12, GPIO_NUM_14 // IF482 serial port parameters //#define HAS_IF482 9600, SERIAL_7E1, GPIO_NUM_12, GPIO_NUM_14 // IF482 serial port parameters
// Settings for DCF77 interface // Settings for DCF77 interface
//#define HAS_DCF77 GPIO_NUM_14 #define HAS_DCF77 GPIO_NUM_14
//#define DCF77_ACTIVE_LOW 1 #define DCF77_ACTIVE_LOW 1
// Settings for external GPS chip // Settings for external GPS chip
//#define HAS_GPS 1 // use on board GPS #define HAS_GPS 1 // use on board GPS
//#define GPS_SERIAL 9600, SERIAL_8N1, GPIO_NUM_17, GPIO_NUM_16 // UBlox NEO 6M or 7M with default configuration #define GPS_SERIAL 9600, SERIAL_8N1, GPIO_NUM_17, GPIO_NUM_16 // UBlox NEO 6M or 7M with default configuration
#define GPS_INT GPIO_NUM_13
// Pins for LORA chip SPI interface, reset line and interrupt lines // Pins for LORA chip SPI interface, reset line and interrupt lines
#define LORA_SCK (5) #define LORA_SCK (5)

View File

@ -82,23 +82,26 @@ not evaluated by model BU-190
#include "if482.h" #include "if482.h"
// Local logging tag // Local logging tag
static const char TAG[] = "main"; static const char TAG[] = __FILE__;
HardwareSerial IF482(2); // use UART #2 (note: #1 may be in use for serial GPS) HardwareSerial IF482(2); // use UART #2 (note: #1 may be in use for serial GPS)
// triggered by timepulse to ticker out DCF signal // triggered by timepulse to send IF482 signal
void IF482_Pulse(time_t t) { void IF482_Pulse(time_t t) {
TickType_t startTime = xTaskGetTickCount(); static const TickType_t txDelay =
static const TickType_t txDelay = pdMS_TO_TICKS(IF482_PULSE_LENGTH) - tx_Ticks(HAS_IF482); pdMS_TO_TICKS(IF482_PULSE_LENGTH - tx_Ticks(IF482_FRAME_SIZE, HAS_IF482));
vTaskDelayUntil(&startTime, txDelay);
IF482.print(IF482_Frame(t+1)); // note: if482 telegram for *next* second //TickType_t startTime = xTaskGetTickCount();
//vTaskDelayUntil(&startTime, txDelay); // wait until moment to fire
vTaskDelay(txDelay); // wait until moment to fire
IF482.print(IF482_Frame(t + 1)); // note: if482 telegram for *next* second
} }
String IRAM_ATTR IF482_Frame(time_t startTime) { String IRAM_ATTR IF482_Frame(time_t startTime) {
time_t t = myTZ.toLocal(startTime); time_t t = myTZ.toLocal(startTime);
char mon, buf[14], out[IF482_FRAME_SIZE]; char mon, out[IF482_FRAME_SIZE];
switch (timeStatus()) { // indicates if time has been set and recently synced switch (timeStatus()) { // indicates if time has been set and recently synced
case timeSet: // time is set and is synced case timeSet: // time is set and is synced
@ -113,24 +116,12 @@ String IRAM_ATTR IF482_Frame(time_t startTime) {
} // switch } // switch
// generate IF482 telegram // generate IF482 telegram
snprintf(buf, sizeof(buf), "%02u%02u%02u%1u%02u%02u%02u", year(t) - 2000, snprintf(out, sizeof(out), "O%cL%02u%02u%02u%1u%02u%02u%02u\r", mon,
month(t), day(t), weekday(t), hour(t), minute(t), second(t)); year(t) - 2000, month(t), day(t), weekday(t), hour(t), minute(t),
snprintf(out, sizeof(out), "O%cL%s\r", mon, buf); second(t));
ESP_LOGD(TAG, "IF482 = %s", out); ESP_LOGD(TAG, "IF482 = %s", out);
return out; return out;
} }
// calculate serial tx time from IF482 serial settings
TickType_t tx_Ticks(unsigned long baud, uint32_t config, int8_t rxPin,
int8_t txPins) {
uint32_t datenbits = ((config & 0x0c) >> 2) + 5;
uint32_t stopbits = ((config & 0x20) >> 5) + 1;
uint32_t tx_delay =
(2 + datenbits + stopbits) * IF482_FRAME_SIZE * 1000.0 / baud;
// +2 ms margin for the startbit and the clock's processing time
return pdMS_TO_TICKS(round(tx_delay));
}
#endif // HAS_IF482 #endif // HAS_IF482

View File

@ -1,7 +1,7 @@
#include "irqhandler.h" #include "irqhandler.h"
// Local logging tag // Local logging tag
static const char TAG[] = "main"; static const char TAG[] = __FILE__;
// irq handler task, handles all our application level interrupts // irq handler task, handles all our application level interrupts
void irqHandler(void *pvParameters) { void irqHandler(void *pvParameters) {
@ -12,8 +12,7 @@ void irqHandler(void *pvParameters) {
// task remains in blocked state until it is notified by an irq // task remains in blocked state until it is notified by an irq
for (;;) { for (;;) {
xTaskNotifyWait( xTaskNotifyWait(0x00, // Don't clear any bits on entry
0x00, // Don't clear any bits on entry
ULONG_MAX, // Clear all bits on exit ULONG_MAX, // Clear all bits on exit
&InterruptStatus, // Receives the notification value &InterruptStatus, // Receives the notification value
portMAX_DELAY); // wait forever portMAX_DELAY); // wait forever
@ -31,8 +30,9 @@ void irqHandler(void *pvParameters) {
#endif #endif
// are cyclic tasks due? // are cyclic tasks due?
if (InterruptStatus & CYCLIC_IRQ) if (InterruptStatus & CYCLIC_IRQ) {
doHousekeeping(); doHousekeeping();
}
// is time to send the payload? // is time to send the payload?
if (InterruptStatus & SENDCOUNTER_IRQ) if (InterruptStatus & SENDCOUNTER_IRQ)

View File

@ -22,7 +22,7 @@
//#define LMIC_USE_INTERRUPTS //#define LMIC_USE_INTERRUPTS
//time sync via LoRaWAN network, is not yet supported by TTN (LoRaWAN spec v1.0.3) //time sync via LoRaWAN network, is not yet supported by TTN (LoRaWAN spec v1.0.3)
//#define LMIC_ENABLE_DeviceTimeReq 1 #define LMIC_ENABLE_DeviceTimeReq 1
// 16 μs per tick // 16 μs per tick
// LMIC requires ticks to be 15.5μs - 100 μs long // LMIC requires ticks to be 15.5μs - 100 μs long

View File

@ -358,12 +358,7 @@ void lora_send(osjob_t *job) {
lora_send); lora_send);
} }
#endif // HAS_LORA
esp_err_t lora_stack_init() { esp_err_t lora_stack_init() {
#ifndef HAS_LORA
return ESP_OK; // continue main program
#else
assert(SEND_QUEUE_SIZE); assert(SEND_QUEUE_SIZE);
LoraSendQueue = xQueueCreate(SEND_QUEUE_SIZE, sizeof(MessageBuffer_t)); LoraSendQueue = xQueueCreate(SEND_QUEUE_SIZE, sizeof(MessageBuffer_t));
if (LoraSendQueue == 0) { if (LoraSendQueue == 0) {
@ -401,12 +396,10 @@ esp_err_t lora_stack_init() {
} }
return ESP_OK; // continue main program return ESP_OK; // continue main program
#endif // HAS_LORA
} }
void lora_enqueuedata(MessageBuffer_t *message, sendprio_t prio) { void lora_enqueuedata(MessageBuffer_t *message, sendprio_t prio) {
// enqueue message in LORA send queue // enqueue message in LORA send queue
#ifdef HAS_LORA
BaseType_t ret; BaseType_t ret;
switch (prio) { switch (prio) {
case prio_high: case prio_high:
@ -423,27 +416,26 @@ void lora_enqueuedata(MessageBuffer_t *message, sendprio_t prio) {
} else { } else {
ESP_LOGW(TAG, "LORA sendqueue is full"); ESP_LOGW(TAG, "LORA sendqueue is full");
} }
#endif
} }
void lora_queuereset(void) { void lora_queuereset(void) { xQueueReset(LoraSendQueue); }
#ifdef HAS_LORA
xQueueReset(LoraSendQueue);
#endif
}
void lora_housekeeping(void) { void lora_housekeeping(void) {
#ifdef HAS_LORA // ESP_LOGD(TAG, "loraloop %d bytes left",
// ESP_LOGD(TAG, "loraloop %d bytes left", // uxTaskGetStackHighWaterMark(LoraTask));
// uxTaskGetStackHighWaterMark(LoraTask));
#endif
} }
void user_request_network_time_callback(void *pVoidUserUTCTime, void user_request_network_time_callback(void *pVoidUserUTCTime,
int flagSuccess) { int flagSuccess) {
#ifdef HAS_LORA
// Explicit conversion from void* to uint32_t* to avoid compiler errors // Explicit conversion from void* to uint32_t* to avoid compiler errors
uint32_t *pUserUTCTime = (uint32_t *)pVoidUserUTCTime; time_t *pUserUTCTime = (time_t *)pVoidUserUTCTime;
// 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 lmicTimeReference; lmic_time_reference_t lmicTimeReference;
if (flagSuccess != 1) { if (flagSuccess != 1) {
@ -459,7 +451,8 @@ void user_request_network_time_callback(void *pVoidUserUTCTime,
} }
// Update userUTCTime, considering the difference between the GPS and UTC // Update userUTCTime, considering the difference between the GPS and UTC
// epoch, and the leap seconds // time, and the leap seconds
// !!! DANGER !!! This code will expire in next year with leap second
*pUserUTCTime = lmicTimeReference.tNetwork + 315964800; *pUserUTCTime = lmicTimeReference.tNetwork + 315964800;
// Current time, in ticks // Current time, in ticks
ostime_t ticksNow = os_getTime(); ostime_t ticksNow = os_getTime();
@ -467,18 +460,17 @@ void user_request_network_time_callback(void *pVoidUserUTCTime,
ostime_t ticksRequestSent = lmicTimeReference.tLocal; ostime_t ticksRequestSent = lmicTimeReference.tLocal;
// Add the delay between the instant the time was transmitted and // Add the delay between the instant the time was transmitted and
// the current time // the current time
uint32_t requestDelaySec = osticks2ms(ticksNow - ticksRequestSent) / 1000; time_t requestDelaySec = osticks2ms(ticksNow - ticksRequestSent) / 1000;
*pUserUTCTime += requestDelaySec; *pUserUTCTime += requestDelaySec;
// Update system time with time read from the network // Update system time with time read from the network
if (sync_TimePulse()) { // wait for start of next second if (timeIsValid(*pUserUTCTime)) {
if (sync_SysTime(*pUserUTCTime)) { // do we have a valid time? xSemaphoreTake(TimePulse, pdMS_TO_TICKS(1000)); // wait for pps
#ifdef HAS_RTC setTime(*pUserUTCTime + 1);
set_rtctime(now()); // epoch time timeSource = _lora;
#endif ESP_LOGI(TAG, "Received recent time from LoRa");
ESP_LOGI(TAG, "LORA has set the system time");
}
} else } else
ESP_LOGI(TAG, "Unable to sync system time with LORA"); ESP_LOGI(TAG, "Invalid time received from LoRa");
#endif // HAS_LORA
} // user_request_network_time_callback } // user_request_network_time_callback
#endif // HAS_LORA

View File

@ -7,7 +7,7 @@
#endif #endif
// Local logging tag // Local logging tag
static const char TAG[] = "main"; static const char TAG[] = __FILE__;
uint16_t salt; uint16_t salt;

View File

@ -27,11 +27,11 @@ Uused tasks and timers:
Task Core Prio Purpose Task Core Prio Purpose
==================================================================================== ====================================================================================
clockloop 0 4 generates realtime telegrams for external clock
ledloop 0 3 blinks LEDs ledloop 0 3 blinks LEDs
spiloop 0 2 reads/writes data on spi interface spiloop 0 2 reads/writes data on spi interface
IDLE 0 0 ESP32 arduino scheduler -> runs wifi sniffer IDLE 0 0 ESP32 arduino scheduler -> runs wifi sniffer
clockloop 1 4 generates realtime telegrams for external clock
looptask 1 1 arduino core -> runs the LMIC LoRa stack looptask 1 1 arduino core -> runs the LMIC LoRa stack
irqhandler 1 1 executes tasks triggered by hw irq, see table below irqhandler 1 1 executes tasks triggered by hw irq, see table below
gpsloop 1 2 reads data from GPS via serial or i2c gpsloop 1 2 reads data from GPS via serial or i2c
@ -52,7 +52,7 @@ ESP32 hardware irq timers
RTC hardware timer (if present) RTC hardware timer (if present)
================================ ================================
triggers IF482 clock signal triggers pps 1 sec impulse
*/ */
@ -65,14 +65,14 @@ uint8_t volatile channel = 0; // channel rotation counter
uint16_t volatile macs_total = 0, macs_wifi = 0, macs_ble = 0, uint16_t volatile macs_total = 0, macs_wifi = 0, macs_ble = 0,
batt_voltage = 0; // globals for display batt_voltage = 0; // globals for display
hw_timer_t *sendCycle = NULL, *homeCycle = NULL; hw_timer_t *sendCycle = NULL, *homeCycle = NULL, *clockCycle = NULL,
#ifdef HAS_DISPLAY *displaytimer = NULL;
hw_timer_t *displaytimer = NULL;
#endif
TaskHandle_t irqHandlerTask, ClockTask; TaskHandle_t irqHandlerTask, ClockTask;
SemaphoreHandle_t I2Caccess, TimePulse; SemaphoreHandle_t I2Caccess, TimePulse;
bool volatile TimePulseTick = false; bool volatile TimePulseTick = false;
time_t userUTCTime = 0;
timesource_t timeSource = _unsynced;
// container holding unique MAC address hashes with Memory Alloctor using PSRAM, // container holding unique MAC address hashes with Memory Alloctor using PSRAM,
// if present // if present
@ -81,13 +81,13 @@ std::set<uint16_t, std::less<uint16_t>, Mallocator<uint16_t>> macs;
// initialize payload encoder // initialize payload encoder
PayloadConvert payload(PAYLOAD_BUFFER_SIZE); PayloadConvert payload(PAYLOAD_BUFFER_SIZE);
// set Time Zone, fetch user setting from paxcounter.conf // set Time Zone for user setting from paxcounter.conf
TimeChangeRule myDST = DAYLIGHT_TIME; TimeChangeRule myDST = DAYLIGHT_TIME;
TimeChangeRule mySTD = STANDARD_TIME; TimeChangeRule mySTD = STANDARD_TIME;
Timezone myTZ(myDST, mySTD); Timezone myTZ(myDST, mySTD);
// local Tag for logging // local Tag for logging
static const char TAG[] = "main"; static const char TAG[] = __FILE__;
void setup() { void setup() {
@ -284,14 +284,14 @@ void setup() {
// initialize LoRa // initialize LoRa
#ifdef HAS_LORA #ifdef HAS_LORA
strcat_P(features, " LORA"); strcat_P(features, " LORA");
#endif
assert(lora_stack_init() == ESP_OK); assert(lora_stack_init() == ESP_OK);
#endif
// initialize SPI // initialize SPI
#ifdef HAS_SPI #ifdef HAS_SPI
strcat_P(features, " SPI"); strcat_P(features, " SPI");
#endif
assert(spi_init() == ESP_OK); assert(spi_init() == ESP_OK);
#endif
#ifdef VENDORFILTER #ifdef VENDORFILTER
strcat_P(features, " OUIFLT"); strcat_P(features, " OUIFLT");
@ -358,12 +358,10 @@ void setup() {
#endif #endif
#endif #endif
// start pps timepulse // start pps timepulse and timekeepr
ESP_LOGI(TAG, "Starting timepulse..."); ESP_LOGI(TAG, "Starting Timekeeper...");
if (timepulse_init()) // setup timepulse assert(timepulse_init()); // setup timepulse
timepulse_start(); // start pulse timepulse_start();
else
ESP_LOGE(TAG, "No timepulse, systime will not be synced!");
// start wifi in monitor mode and start channel rotation timer // start wifi in monitor mode and start channel rotation timer
ESP_LOGI(TAG, "Starting Wifi..."); ESP_LOGI(TAG, "Starting Wifi...");
@ -416,30 +414,9 @@ void setup() {
#endif #endif
#endif // HAS_BUTTON #endif // HAS_BUTTON
#ifdef HAS_GPS // set time source
// sync systime on next timepulse setSyncInterval(TIME_SYNC_INTERVAL * 60);
ESP_LOGI(TAG, "GPS is setting system time"); setSyncProvider(&timeProvider);
if (sync_SysTime(get_gpstime())) {
//setSyncProvider(get_gpstime); // reset sync cycle on top of second
//setSyncInterval(TIME_SYNC_INTERVAL_GPS * 60);
// calibrate RTC
#ifdef HAS_RTC
set_rtctime(now()); // epoch time
#endif
} else
ESP_LOGI(TAG, "Unable to sync system time with GPS");
#endif // HAS_GPS
// initialize systime from timesource
#ifdef HAS_RTC
// sync systime on next timepulse
ESP_LOGI(TAG, "RTC is setting system time");
if (sync_SysTime(get_rtctime())) {
//setSyncProvider(get_rtctime); // reset sync cycle on top of second
//setSyncInterval(TIME_SYNC_INTERVAL_RTC * 60);
} else
ESP_LOGI(TAG, "Unable to sync system time with RTC");
#endif // HAS_RTC
#if defined HAS_IF482 || defined HAS_DCF77 #if defined HAS_IF482 || defined HAS_DCF77
ESP_LOGI(TAG, "Starting Clock Controller..."); ESP_LOGI(TAG, "Starting Clock Controller...");

View File

@ -31,7 +31,7 @@ int volatile contentLength = 0;
bool volatile isValidContentType = false; bool volatile isValidContentType = false;
// Local logging tag // Local logging tag
static const char TAG[] = "main"; static const char TAG[] = __FILE__;
// helper function to extract header value from header // helper function to extract header value from header
inline String getHeaderValue(String header, String headerName) { inline String getHeaderValue(String header, String headerName) {

View File

@ -11,7 +11,7 @@
// Payload send cycle and encoding // Payload send cycle and encoding
#define SEND_SECS 30 // payload send cycle [seconds/2] -> 60 sec. #define SEND_SECS 30 // payload send cycle [seconds/2] -> 60 sec.
#define PAYLOAD_ENCODER 2 // payload encoder: 1=Plain, 2=Packed, 3=CayenneLPP dynamic, 4=CayenneLPP packed #define PAYLOAD_ENCODER 2 // payload encoder: 1=Plain, 2=Packed, 3=Cayenne LPP dynamic, 4=Cayenne LPP packed
// Set this to include BLE counting and vendor filter functions // Set this to include BLE counting and vendor filter functions
#define VENDORFILTER 1 // comment out if you want to count things, not people #define VENDORFILTER 1 // comment out if you want to count things, not people
@ -49,28 +49,12 @@
#define MAXLORARETRY 500 // maximum count of TX retries if LoRa busy #define MAXLORARETRY 500 // maximum count of TX retries if LoRa busy
#define SEND_QUEUE_SIZE 10 // maximum number of messages in payload send queue [1 = no queue] #define SEND_QUEUE_SIZE 10 // maximum number of messages in payload send queue [1 = no queue]
// Ports on which the device sends and listenes on LoRaWAN and SPI // Hardware settings
#define COUNTERPORT 1 // Port on which device sends counts
#define RCMDPORT 2 // Port on which device listenes for remote commands
#define STATUSPORT 2 // Port on which device sends remote command results
#define CONFIGPORT 3 // Port on which device sends config query results
#define GPSPORT 4 // Port on which device sends gps data
#define BUTTONPORT 5 // Port on which device sends button pressed signal
#define LPP1PORT 1 // Port for Cayenne LPP 1.0 dynamic sensor encoding
#define LPP2PORT 2 // Port for Cayenne LPP 2.0 packed sensor encoding
#define BEACONPORT 6 // Port on which device sends beacon alarms
#define BMEPORT 7 // Port on which device sends BME680 sensor data
#define BATTPORT 8 // Port on which device sends battery voltage data
#define SENSOR1PORT 10 // Port on which device sends User sensor #1 data
#define SENSOR2PORT 11 // Port on which device sends User sensor #2 data
#define SENSOR3PORT 12 // Port on which device sends User sensor #3 data
// Some hardware settings
#define RGBLUMINOSITY 30 // RGB LED luminosity [default = 30%] #define RGBLUMINOSITY 30 // RGB LED luminosity [default = 30%]
#define DISPLAYREFRESH_MS 40 // OLED refresh cycle in ms [default = 40] -> 1000/40 = 25 frames per second #define DISPLAYREFRESH_MS 40 // OLED refresh cycle in ms [default = 40] -> 1000/40 = 25 frames per second
#define HOMECYCLE 30 // house keeping cycle in seconds [default = 30 secs] #define HOMECYCLE 30 // house keeping cycle in seconds [default = 30 secs]
// Settings for BME680 environmental sensor (if present) // Settings for BME680 environmental sensor
#define BME_TEMP_OFFSET 5.0f // Offset sensor on chip temp <-> ambient temp [default = 5°C] #define BME_TEMP_OFFSET 5.0f // Offset sensor on chip temp <-> ambient temp [default = 5°C]
#define STATE_SAVE_PERIOD UINT32_C(360 * 60 * 1000) // update every 360 minutes = 4 times a day #define STATE_SAVE_PERIOD UINT32_C(360 * 60 * 1000) // update every 360 minutes = 4 times a day
@ -81,14 +65,37 @@
#define OTA_MIN_BATT 3600 // minimum battery level for OTA [millivolt] #define OTA_MIN_BATT 3600 // minimum battery level for OTA [millivolt]
#define RESPONSE_TIMEOUT_MS 60000 // firmware binary server connection timeout [milliseconds] #define RESPONSE_TIMEOUT_MS 60000 // firmware binary server connection timeout [milliseconds]
// settings for syncing time of node and external time sources // settings for syncing time of node with external time source
#define TIME_SYNC_INTERVAL_GPS 5 // sync time each .. minutes from GPS [default = 5], comment out means off #define TIME_SYNC_INTERVAL 2 // sync time attempt each .. minutes from time source (GPS/LORA/RTC) [default = 60], comment out means off
#define TIME_SYNC_INTERVAL_RTC 60 // sync time each .. minutes from RTC [default = 60], comment out means off //#define TIME_SYNC_LORA 1 // use LORA network as time source, comment out means off [default = off]
//#define TIME_SYNC_INTERVAL_LORA 60 // sync time each .. minutes from LORA network [default = 60], comment out means off
// time zone, see https://github.com/JChristensen/Timezone/blob/master/examples/WorldClock/WorldClock.ino // time zone, see https://github.com/JChristensen/Timezone/blob/master/examples/WorldClock/WorldClock.ino
#define DAYLIGHT_TIME {"CEST", Last, Sun, Mar, 2, 120} // Central European Summer Time #define DAYLIGHT_TIME {"CEST", Last, Sun, Mar, 2, 120} // Central European Summer Time
#define STANDARD_TIME {"CET ", Last, Sun, Oct, 3, 60} // Central European Standard Time #define STANDARD_TIME {"CET ", Last, Sun, Oct, 3, 60} // Central European Standard Time
// Ports on which the device sends and listenes on LoRaWAN and SPI
#define COUNTERPORT 1 // counts
#define RCMDPORT 2 // remote commands
#define STATUSPORT 2 // remote command results
#define CONFIGPORT 3 // config query results
#define GPSPORT 4 // gps
#define BUTTONPORT 5 // button pressed signal
#define BEACONPORT 6 // beacon alarms
#define BMEPORT 7 // BME680 sensor
#define BATTPORT 8 // battery voltage
#define TIMEPORT 9 // time
#define SENSOR1PORT 10 // user sensor #1
#define SENSOR2PORT 11 // user sensor #2
#define SENSOR3PORT 12 // user sensor #3
// Cayenne LPP Ports, see https://community.mydevices.com/t/cayenne-lpp-2-0/7510
#define CAYENNE_LPP1 1 // dynamic sensor payload (LPP 1.0)
#define CAYENNE_LPP2 2 // packed sensor payload (LPP 2.0)
#define CAYENNE_GPS 3 // full scale GPS payload
#define CAYENNE_ACTUATOR 10 // actuator commands
#define CAYENNE_DEVICECONFIG 11 // device period configuration
#define CAYENNE_SENSORREAD 13 // sensor period configuration
#define CAYENNE_SENSORENABLE 14 // sensor enable configuration
// LMIC settings // LMIC settings
// moved to src/lmic_config.h // -> in src/lmic_config.h

View File

@ -126,6 +126,14 @@ void PayloadConvert::addButton(uint8_t value) {
#endif #endif
} }
void PayloadConvert::addTime(time_t value) {
uint32_t time = (uint32_t)value;
buffer[cursor++] = (byte)((time & 0xFF000000) >> 24);
buffer[cursor++] = (byte)((time & 0x00FF0000) >> 16);
buffer[cursor++] = (byte)((time & 0x0000FF00) >> 8);
buffer[cursor++] = (byte)((time & 0x000000FF));
}
/* ---------------- packed format with LoRa serialization Encoder ---------- /* ---------------- packed format with LoRa serialization Encoder ----------
*/ */
// derived from // derived from
@ -133,7 +141,9 @@ void PayloadConvert::addButton(uint8_t value) {
#elif PAYLOAD_ENCODER == 2 #elif PAYLOAD_ENCODER == 2
void PayloadConvert::addCount(uint16_t value, uint8_t snifftype) { writeUint16(value); } void PayloadConvert::addCount(uint16_t value, uint8_t snifftype) {
writeUint16(value);
}
void PayloadConvert::addAlarm(int8_t rssi, uint8_t msg) { void PayloadConvert::addAlarm(int8_t rssi, uint8_t msg) {
writeUint8(rssi); writeUint8(rssi);
@ -208,6 +218,11 @@ void PayloadConvert::addButton(uint8_t value) {
#endif #endif
} }
void PayloadConvert::addTime(time_t value) {
uint32_t time = (uint32_t)value;
writeUint32(time);
}
void PayloadConvert::intToBytes(uint8_t pos, int32_t i, uint8_t byteSize) { void PayloadConvert::intToBytes(uint8_t pos, int32_t i, uint8_t byteSize) {
for (uint8_t x = 0; x < byteSize; x++) { for (uint8_t x = 0; x < byteSize; x++) {
buffer[x + pos] = (byte)(i >> (x * 8)); buffer[x + pos] = (byte)(i >> (x * 8));
@ -275,14 +290,16 @@ void PayloadConvert::writeBitmap(bool a, bool b, bool c, bool d, bool e, bool f,
} }
/* ---------------- Cayenne LPP 2.0 format ---------- */ /* ---------------- Cayenne LPP 2.0 format ---------- */
// see specs http://community.mydevices.com/t/cayenne-lpp-2-0/7510 // see specs
// http://community.mydevices.com/t/cayenne-lpp-2-0/7510 (LPP 2.0)
// https://github.com/myDevicesIoT/cayenne-docs/blob/master/docs/LORA.md (LPP 1.0)
// PAYLOAD_ENCODER == 3 -> Dynamic Sensor Payload, using channels -> FPort 1 // PAYLOAD_ENCODER == 3 -> Dynamic Sensor Payload, using channels -> FPort 1
// PAYLOAD_ENCODER == 4 -> Packed Sensor Payload, not using channels -> FPort 2 // PAYLOAD_ENCODER == 4 -> Packed Sensor Payload, not using channels -> FPort 2
#elif (PAYLOAD_ENCODER == 3 || PAYLOAD_ENCODER == 4) #elif (PAYLOAD_ENCODER == 3 || PAYLOAD_ENCODER == 4)
void PayloadConvert::addCount(uint16_t value, uint8_t snifftype) { void PayloadConvert::addCount(uint16_t value, uint8_t snifftype) {
switch(snifftype) { switch (snifftype) {
case MAC_SNIFF_WIFI: case MAC_SNIFF_WIFI:
#if (PAYLOAD_ENCODER == 3) #if (PAYLOAD_ENCODER == 3)
buffer[cursor++] = LPP_COUNT_WIFI_CHANNEL; buffer[cursor++] = LPP_COUNT_WIFI_CHANNEL;
@ -436,6 +453,24 @@ void PayloadConvert::addButton(uint8_t value) {
#endif // HAS_BUTTON #endif // HAS_BUTTON
} }
void PayloadConvert::addTime(time_t value) {
#if (PAYLOAD_ENCODER == 4)
uint32_t t = (uint32_t)value;
uint32_t tx_period = (uint32_t)SEND_SECS * 2;
buffer[cursor++] = 0x03; // set config mask to UTCTime + TXPeriod
// UTCTime in seconds
buffer[cursor++] = (byte)((t & 0xFF000000) >> 24);
buffer[cursor++] = (byte)((t & 0x00FF0000) >> 16);
buffer[cursor++] = (byte)((t & 0x0000FF00) >> 8);
buffer[cursor++] = (byte)((t & 0x000000FF));
// TXPeriod in seconds
buffer[cursor++] = (byte)((tx_period & 0xFF000000) >> 24);
buffer[cursor++] = (byte)((tx_period & 0x00FF0000) >> 16);
buffer[cursor++] = (byte)((tx_period & 0x0000FF00) >> 8);
buffer[cursor++] = (byte)((tx_period & 0x000000FF));
#endif
}
#else #else
#error No valid payload converter defined! #error No valid payload converter defined!
#endif #endif

View File

@ -3,7 +3,7 @@
#include "rcommand.h" #include "rcommand.h"
// Local logging tag // Local logging tag
static const char TAG[] = "main"; static const char TAG[] = __FILE__;
// helper function // helper function
void do_reset() { void do_reset() {
@ -68,7 +68,7 @@ void set_sendcycle(uint8_t val[]) {
void set_wifichancycle(uint8_t val[]) { void set_wifichancycle(uint8_t val[]) {
cfg.wifichancycle = val[0]; cfg.wifichancycle = val[0];
// update Wifi channel rotation timer period // update Wifi channel rotation timer period
xTimerChangePeriod(WifiChanTimer, pdMS_TO_TICKS(cfg.wifichancycle * 10), 100 ); xTimerChangePeriod(WifiChanTimer, pdMS_TO_TICKS(cfg.wifichancycle * 10), 100);
ESP_LOGI(TAG, ESP_LOGI(TAG,
"Remote command: set Wifi channel switch interval to %.1f seconds", "Remote command: set Wifi channel switch interval to %.1f seconds",
@ -244,9 +244,8 @@ void get_status(uint8_t val[]) {
uint16_t voltage = 0; uint16_t voltage = 0;
#endif #endif
payload.reset(); payload.reset();
payload.addStatus(voltage, uptime() / 1000, temperatureRead(), payload.addStatus(voltage, uptime() / 1000, temperatureRead(), getFreeRAM(),
getFreeRAM(), rtc_get_reset_reason(0), rtc_get_reset_reason(0), rtc_get_reset_reason(1));
rtc_get_reset_reason(1));
SendPayload(STATUSPORT, prio_high); SendPayload(STATUSPORT, prio_high);
}; };
@ -273,6 +272,13 @@ void get_bme(uint8_t val[]) {
#endif #endif
}; };
void get_time(uint8_t val[]) {
ESP_LOGI(TAG, "Remote command: get time");
payload.reset();
payload.addTime(now());
SendPayload(TIMEPORT, prio_high);
};
// assign previously defined functions to set of numeric remote commands // assign previously defined functions to set of numeric remote commands
// format: opcode, function, #bytes params, // format: opcode, function, #bytes params,
// flag (true = do make settings persistent / false = don't) // flag (true = do make settings persistent / false = don't)
@ -289,7 +295,7 @@ cmd_t table[] = {
{0x11, set_monitor, 1, true}, {0x12, set_beacon, 7, false}, {0x11, set_monitor, 1, true}, {0x12, set_beacon, 7, false},
{0x13, set_sensor, 2, true}, {0x80, get_config, 0, false}, {0x13, set_sensor, 2, true}, {0x80, get_config, 0, false},
{0x81, get_status, 0, false}, {0x84, get_gps, 0, false}, {0x81, get_status, 0, false}, {0x84, get_gps, 0, false},
{0x85, get_bme, 0, false}, {0x85, get_bme, 0, false}, {0x86, get_time, 0, false},
}; };
const uint8_t cmdtablesize = const uint8_t cmdtablesize =

View File

@ -1,214 +1,81 @@
#include "rtctime.h" #include "rtctime.h"
// Local logging tag // Local logging tag
static const char TAG[] = "main"; static const char TAG[] = __FILE__;
hw_timer_t *clockCycle = NULL;
// helper function to setup a pulse per second for time synchronisation
int timepulse_init() {
// use time pulse from GPS as time base with fixed 1Hz frequency
#ifdef GPS_INT
// setup external interupt for active low RTC INT pin
pinMode(GPS_INT, INPUT_PULLDOWN);
// setup external rtc 1Hz clock as pulse per second clock
ESP_LOGI(TAG, "Time base: external (GPS)");
return 1; // success
// use pulse from on board RTC chip as time base with fixed frequency
#elif defined RTC_INT
// setup external interupt for active low RTC INT pin
pinMode(RTC_INT, INPUT_PULLUP);
// setup external rtc 1Hz clock as pulse per second clock
if (I2C_MUTEX_LOCK()) {
Rtc.SetSquareWavePinClockFrequency(DS3231SquareWaveClock_1Hz);
Rtc.SetSquareWavePin(DS3231SquareWavePin_ModeClock);
I2C_MUTEX_UNLOCK();
ESP_LOGI(TAG, "Time base: external (RTC)");
return 1; // success
} else {
ESP_LOGE(TAG, "I2c bus busy - RTC initialization error");
return 0; // failure
}
return 1; // success
#else
// use ESP32 hardware timer as time base with adjustable frequency
clockCycle = timerBegin(1, 8000, true); // set 80 MHz prescaler to 1/10000 sec
timerAlarmWrite(clockCycle, 10000, true); // 1000ms
ESP_LOGI(TAG, "Time base: internal (ESP32 hardware timer)");
return 1; // success
#endif
} // timepulse_init
void timepulse_start(void) {
#ifdef GPS_INT // start external clock gps pps line
attachInterrupt(digitalPinToInterrupt(GPS_INT), CLOCKIRQ, RISING);
#elif defined RTC_INT // start external clock rtc
attachInterrupt(digitalPinToInterrupt(RTC_INT), CLOCKIRQ, FALLING);
#else // start internal clock esp32 hardware timer
timerAttachInterrupt(clockCycle, &CLOCKIRQ, true);
timerAlarmEnable(clockCycle);
#endif
}
// interrupt service routine triggered by either pps or esp32 hardware timer
void IRAM_ATTR CLOCKIRQ(void) {
if (ClockTask != NULL)
xTaskNotifyFromISR(ClockTask, xTaskGetTickCountFromISR(), eSetBits, NULL);
#if defined GPS_INT || defined RTC_INT
xSemaphoreGiveFromISR(TimePulse, NULL);
TimePulseTick = !TimePulseTick; // flip ticker
#endif
portYIELD_FROM_ISR();
}
// helper function to sync systime on start of next second
int sync_SysTime(time_t t) {
if (sync_TimePulse() && (t)) { // wait for start of next second by timepulse
setTime(t + 1);
ESP_LOGD(TAG, "Systime synced on second");
return 1; // success
} else
return 0; // failure
}
int sync_SysTime(uint32_t t) { // t is epoch seconds starting 1.1.1970
return sync_SysTime(static_cast<time_t>(t));
}
// helper function to sync moment on timepulse
int sync_TimePulse(void) {
// sync on top of next second by timepulse
if (xSemaphoreTake(TimePulse, pdMS_TO_TICKS(1100)) == pdTRUE) {
return 1;
} // success
else
ESP_LOGW(TAG, "Missing timepulse, time not synced");
return 0; // failure
}
// helper function to fetch current second from most precise time source
time_t best_time(void) {
time_t t;
#ifdef HAS_GPS // gps is our primary time source if present
t = get_gpstime();
if (t) // did we get a valid time?
return t;
#endif
/*
// Reading RTC time from chip take too long on i2c bus, causes jitter
#ifdef HAS_RTC // rtc is our secondary time source if present
t = get_rtctime();
if (t)
return t;
#endif
*/
// else we use systime as fallback source
return now();
}
#ifdef HAS_RTC // we have hardware RTC #ifdef HAS_RTC // we have hardware RTC
RtcDS3231<TwoWire> Rtc(Wire); // RTC hardware i2c interface RtcDS3231<TwoWire> Rtc(Wire); // RTC hardware i2c interface
// initialize RTC // initialize RTC
int rtc_init(void) { uint8_t rtc_init(void) {
// return = 0 -> error / return = 1 -> success if (I2C_MUTEX_LOCK()) { // block i2c bus access
// block i2c bus access
if (I2C_MUTEX_LOCK()) {
Wire.begin(HAS_RTC); Wire.begin(HAS_RTC);
Rtc.Begin(); Rtc.Begin();
RtcDateTime compiled = RtcDateTime(__DATE__, __TIME__); // configure RTC chip
Rtc.Enable32kHzPin(false);
if (!Rtc.IsDateTimeValid()) { Rtc.SetSquareWavePin(DS3231SquareWavePin_ModeNone);
ESP_LOGW(TAG,
"RTC has no valid RTC date/time, setting to compilation date");
Rtc.SetDateTime(compiled);
}
if (!Rtc.GetIsRunning()) { if (!Rtc.GetIsRunning()) {
ESP_LOGI(TAG, "RTC not running, starting now"); ESP_LOGI(TAG, "RTC not running, starting now");
Rtc.SetIsRunning(true); Rtc.SetIsRunning(true);
} }
RtcDateTime now = Rtc.GetDateTime(); // If you want to initialize a fresh RTC to compiled time, use this code
/*
RtcDateTime tt = Rtc.GetDateTime();
time_t t = tt.Epoch32Time(); // sec2000 -> epoch
if (now < compiled) { if (!Rtc.IsDateTimeValid() || !timeIsValid(t)) {
ESP_LOGI(TAG, "RTC date/time is older than compilation date, updating"); ESP_LOGW(TAG, "RTC has no recent time, setting to compilation date");
Rtc.SetDateTime(compiled); Rtc.SetDateTime(
} RtcDateTime(compiledUTC() - SECS_YR_2000)); // epoch -> sec2000
// configure RTC chip
Rtc.Enable32kHzPin(false);
Rtc.SetSquareWavePin(DS3231SquareWavePin_ModeNone);
} else {
ESP_LOGE(TAG, "I2c bus busy - RTC initialization error");
goto error;
} }
*/
I2C_MUTEX_UNLOCK(); // release i2c bus access I2C_MUTEX_UNLOCK(); // release i2c bus access
ESP_LOGI(TAG, "RTC initialized"); ESP_LOGI(TAG, "RTC initialized");
return 1; return 1; // success
} else {
error: ESP_LOGE(TAG, "RTC initialization error, I2C bus busy");
I2C_MUTEX_UNLOCK(); // release i2c bus access return 0; // failure
return 0; }
} // rtc_init() } // rtc_init()
int set_rtctime(time_t t) { // t is seconds epoch time starting 1.1.1970 uint8_t set_rtctime(time_t t) { // t is UTC in seconds epoch time
if (I2C_MUTEX_LOCK()) { if (I2C_MUTEX_LOCK()) {
Rtc.SetDateTime(RtcDateTime(t)); Rtc.SetDateTime(RtcDateTime(t - SECS_YR_2000)); // epoch -> sec2000
I2C_MUTEX_UNLOCK(); // release i2c bus access I2C_MUTEX_UNLOCK();
ESP_LOGI(TAG, "RTC calibrated"); ESP_LOGI(TAG, "RTC time synced");
return 1; // success return 1; // success
} } else {
ESP_LOGE(TAG, "RTC set time failure"); ESP_LOGE(TAG, "RTC set time failure");
return 0; // failure return 0;
} // failure
} // set_rtctime() } // set_rtctime()
int set_rtctime(uint32_t t) { // t is epoch seconds starting 1.1.1970
return set_rtctime(static_cast<time_t>(t));
// set_rtctime()
}
time_t get_rtctime(void) { time_t get_rtctime(void) {
// !! never call now() or delay in this function, this would break this time_t t = 0;
// function to be used as SyncProvider for Time.h
time_t t = 0; // 0 effects calling SyncProvider() to not set time
// block i2c bus access
if (I2C_MUTEX_LOCK()) { if (I2C_MUTEX_LOCK()) {
if (Rtc.IsDateTimeValid()) { if (Rtc.IsDateTimeValid() && Rtc.GetIsRunning()) {
RtcDateTime tt = Rtc.GetDateTime(); RtcDateTime tt = Rtc.GetDateTime();
t = tt.Epoch32Time(); t = tt.Epoch32Time(); // sec2000 -> epoch
} }
I2C_MUTEX_UNLOCK(); // release i2c bus access I2C_MUTEX_UNLOCK();
} }
return t; return timeIsValid(t);
} // get_rtctime() } // get_rtctime()
float get_rtctemp(void) { float get_rtctemp(void) {
// block i2c bus access
if (I2C_MUTEX_LOCK()) { if (I2C_MUTEX_LOCK()) {
RtcTemperature temp = Rtc.GetTemperature(); RtcTemperature temp = Rtc.GetTemperature();
I2C_MUTEX_UNLOCK(); // release i2c bus access I2C_MUTEX_UNLOCK();
return temp.AsFloatDegC(); return temp.AsFloatDegC();
} // while }
return 0; return 0;
} // get_rtctemp() } // get_rtctemp()

View File

@ -8,24 +8,39 @@ void SendPayload(uint8_t port, sendprio_t prio) {
SendBuffer.MessageSize = payload.getSize(); SendBuffer.MessageSize = payload.getSize();
switch (PAYLOAD_ENCODER) { switch (PAYLOAD_ENCODER) {
case 1: case 1: // plain -> no mapping
case 2: case 2: // packed -> no mapping
SendBuffer.MessagePort = port; SendBuffer.MessagePort = port;
break; break;
case 3: case 3: // Cayenne LPP dynamic -> all payload goes out on same port
SendBuffer.MessagePort = LPP1PORT; SendBuffer.MessagePort = CAYENNE_LPP1;
break; break;
case 4: case 4: // Cayenne LPP packed -> we need to map some paxcounter ports
SendBuffer.MessagePort = LPP2PORT; SendBuffer.MessagePort = CAYENNE_LPP2;
switch (SendBuffer.MessagePort) {
case COUNTERPORT:
SendBuffer.MessagePort = CAYENNE_LPP2;
break;
case RCMDPORT:
SendBuffer.MessagePort = CAYENNE_ACTUATOR;
break;
case TIMEPORT:
SendBuffer.MessagePort = CAYENNE_DEVICECONFIG;
break;
}
break; break;
default: default:
SendBuffer.MessagePort = port; SendBuffer.MessagePort = port;
} }
memcpy(SendBuffer.Message, payload.getBuffer(), payload.getSize()); memcpy(SendBuffer.Message, payload.getBuffer(), payload.getSize());
// enqueue message in device's send queues // enqueue message in device's send queues
#ifdef HAS_LORA
lora_enqueuedata(&SendBuffer, prio); lora_enqueuedata(&SendBuffer, prio);
#endif
#ifdef HAS_SPI
spi_enqueuedata(&SendBuffer, prio); spi_enqueuedata(&SendBuffer, prio);
#endif
} // SendPayload } // SendPayload
@ -119,6 +134,10 @@ void sendCounter() {
} // sendCounter() } // sendCounter()
void flushQueues() { void flushQueues() {
#ifdef HAS_LORA
lora_queuereset(); lora_queuereset();
#endif
#ifdef HAS_SPI
spi_queuereset(); spi_queuereset();
#endif
} }

View File

@ -2,7 +2,7 @@
#include "globals.h" #include "globals.h"
// Local logging tag // Local logging tag
static const char TAG[] = "main"; static const char TAG[] = __FILE__;
#define SENSORBUFFER \ #define SENSORBUFFER \
10 // max. size of user sensor data buffer in bytes [default=20] 10 // max. size of user sensor data buffer in bytes [default=20]

View File

@ -22,6 +22,8 @@ licenses. Refer to LICENSE.txt file in repository for more details.
*/ */
#ifdef HAS_SPI
#include "spislave.h" #include "spislave.h"
#include <driver/spi_slave.h> #include <driver/spi_slave.h>
@ -102,9 +104,6 @@ void spi_slave_task(void *param) {
} }
esp_err_t spi_init() { esp_err_t spi_init() {
#ifndef HAS_SPI
return ESP_OK;
#else
assert(SEND_QUEUE_SIZE); assert(SEND_QUEUE_SIZE);
SPISendQueue = xQueueCreate(SEND_QUEUE_SIZE, sizeof(MessageBuffer_t)); SPISendQueue = xQueueCreate(SEND_QUEUE_SIZE, sizeof(MessageBuffer_t));
if (SPISendQueue == 0) { if (SPISendQueue == 0) {
@ -146,13 +145,10 @@ esp_err_t spi_init() {
} }
return ret; return ret;
#endif
} }
void spi_enqueuedata(MessageBuffer_t *message, sendprio_t prio) { void spi_enqueuedata(MessageBuffer_t *message, sendprio_t prio) {
// enqueue message in SPI send queue // enqueue message in SPI send queue
#ifdef HAS_SPI
BaseType_t ret; BaseType_t ret;
switch (prio) { switch (prio) {
case prio_high: case prio_high:
@ -170,17 +166,12 @@ void spi_enqueuedata(MessageBuffer_t *message, sendprio_t prio) {
} else { } else {
ESP_LOGW(TAG, "SPI sendqueue is full"); ESP_LOGW(TAG, "SPI sendqueue is full");
} }
#endif
} }
void spi_queuereset(void) { void spi_queuereset(void) { xQueueReset(SPISendQueue); }
#ifdef HAS_SPI
xQueueReset(SPISendQueue);
#endif
}
void spi_housekeeping(void) { void spi_housekeeping(void) {
#ifdef HAS_SPI
ESP_LOGD(TAG, "spiloop %d bytes left", uxTaskGetStackHighWaterMark(spiTask)); ESP_LOGD(TAG, "spiloop %d bytes left", uxTaskGetStackHighWaterMark(spiTask));
#endif
} }
#endif // HAS_SPI

231
src/timekeeper.cpp Normal file
View File

@ -0,0 +1,231 @@
#include "timekeeper.h"
// Local logging tag
static const char TAG[] = __FILE__;
// symbol to display current time source
const char timeSetSymbols[] = {'G', 'R', 'L', '?'};
getExternalTime TimeSourcePtr; // pointer to time source function
time_t timeProvider(void) {
ESP_LOGD(TAG, "time synched");
time_t t = 0;
#ifdef HAS_GPS
// xSemaphoreTake(TimePulse, pdMS_TO_TICKS(1100)); // wait for pps
t = get_gpstime(); // fetch recent time from last NEMA record
if (t) {
// t++; // last NMEA record concerns past second, so we add one
#ifdef HAS_RTC
set_rtctime(t); // calibrate RTC
#endif
timeSource = _gps;
return t;
}
#endif
// no GPS -> fallback to RTC time while trying lora sync
#ifdef HAS_RTC
t = get_rtctime();
if (t) {
timeSource = _rtc;
}
#endif
// kick off asychron lora sync if we have
#if defined HAS_LORA && defined TIME_SYNC_LORA
LMIC_requestNetworkTime(user_request_network_time_callback, &userUTCTime);
#endif
if (!t)
timeSource = _unsynced;
return t;
} // timeProvider()
// helper function to setup a pulse per second for time synchronisation
uint8_t timepulse_init() {
// use time pulse from GPS as time base with fixed 1Hz frequency
#ifdef GPS_INT
// setup external interupt pin for rising edge GPS INT
pinMode(GPS_INT, INPUT_PULLDOWN);
// setup external rtc 1Hz clock as pulse per second clock
ESP_LOGI(TAG, "Timepulse: external (GPS)");
return 1; // success
// use pulse from on board RTC chip as time base with fixed frequency
#elif defined RTC_INT
// setup external interupt pin for falling edge RTC INT
pinMode(RTC_INT, INPUT_PULLUP);
// setup external rtc 1Hz clock as pulse per second clock
if (I2C_MUTEX_LOCK()) {
Rtc.SetSquareWavePinClockFrequency(DS3231SquareWaveClock_1Hz);
Rtc.SetSquareWavePin(DS3231SquareWavePin_ModeClock);
I2C_MUTEX_UNLOCK();
ESP_LOGI(TAG, "Timepulse: external (RTC)");
return 1; // success
} else {
ESP_LOGE(TAG, "RTC initialization error, I2C bus busy");
return 0; // failure
}
return 1; // success
#else
// use ESP32 hardware timer as time base with adjustable frequency
clockCycle = timerBegin(1, 8000, true); // set 80 MHz prescaler to 1/10000 sec
timerAlarmWrite(clockCycle, 10000, true); // 1000ms
ESP_LOGI(TAG, "Timepulse: internal (ESP32 hardware timer)");
return 1; // success
#endif
} // timepulse_init
void timepulse_start(void) {
#ifdef GPS_INT // start external clock gps pps line
attachInterrupt(digitalPinToInterrupt(GPS_INT), CLOCKIRQ, RISING);
#elif defined RTC_INT // start external clock rtc
attachInterrupt(digitalPinToInterrupt(RTC_INT), CLOCKIRQ, FALLING);
#else // start internal clock esp32 hardware timer
timerAttachInterrupt(clockCycle, &CLOCKIRQ, true);
timerAlarmEnable(clockCycle);
#endif
}
// interrupt service routine triggered by either pps or esp32 hardware timer
void IRAM_ATTR CLOCKIRQ(void) {
SyncToPPS(); // calibrate systime from Time.h
if (ClockTask != NULL)
xTaskNotifyFromISR(ClockTask, uint32_t(now()), eSetBits, NULL);
#if defined GPS_INT || defined RTC_INT
xSemaphoreGiveFromISR(TimePulse, NULL);
TimePulseTick = !TimePulseTick; // flip ticker
#endif
portYIELD_FROM_ISR();
}
// helper function to check plausibility of a time
time_t timeIsValid(time_t const t) {
// is it a time in the past? we use compile date to guess
return (t >= compiledUTC() ? t : 0);
}
// helper function to convert compile time to UTC time
time_t compiledUTC(void) {
static time_t t = myTZ.toUTC(RtcDateTime(__DATE__, __TIME__).Epoch32Time());
return t;
}
// helper function to convert gps date/time into time_t
time_t tmConvert(uint16_t YYYY, uint8_t MM, uint8_t DD, uint8_t hh, uint8_t mm,
uint8_t ss) {
tmElements_t tm;
tm.Year = CalendarYrToTm(YYYY); // year offset from 1970 in time.h
tm.Month = MM;
tm.Day = DD;
tm.Hour = hh;
tm.Minute = mm;
tm.Second = ss;
return makeTime(tm);
}
// helper function to calculate serial transmit time
TickType_t tx_Ticks(uint32_t framesize, unsigned long baud, uint32_t config,
int8_t rxPin, int8_t txPins) {
uint32_t databits = ((config & 0x0c) >> 2) + 5;
uint32_t stopbits = ((config & 0x20) >> 5) + 1;
uint32_t txTime = (databits + stopbits + 2) * framesize * 1000.0 / baud;
// +1 ms margin for the startbit +1 ms for pending processing time
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) {
// setup clock output interface
#ifdef HAS_IF482
IF482.begin(HAS_IF482);
#elif defined HAS_DCF77
pinMode(HAS_DCF77, OUTPUT);
#endif
xTaskCreatePinnedToCore(clock_loop, // task function
"clockloop", // name of task
2048, // stack size of task
(void *)1, // task parameter
4, // priority of the task
&ClockTask, // task handle
1); // CPU core
assert(ClockTask); // has clock task started?
} // clock_init
void clock_loop(void *pvParameters) { // ClockTask
configASSERT(((uint32_t)pvParameters) == 1); // FreeRTOS check
TickType_t wakeTime;
uint32_t printtime;
time_t t;
#define t1(t) (t + DCF77_FRAME_SIZE + 1) // future minute for next DCF77 frame
#define t2(t) (t + 1) // future second after sync with 1pps trigger
// preload first DCF frame before start
#ifdef HAS_DCF77
uint8_t *DCFpulse; // pointer on array with DCF pulse bits
DCFpulse = DCF77_Frame(t1(now()));
#endif
// output time telegram for second following sec beginning with timepulse
for (;;) {
xTaskNotifyWait(0x00, ULONG_MAX, &printtime,
portMAX_DELAY); // wait for timepulse
// no confident time -> suppress clock output
if (timeStatus() == timeNotSet)
continue;
t = time_t(printtime);
#if defined HAS_IF482
// IF482_Pulse(t2(t)); // next second
IF482_Pulse(t); // next second
#elif defined HAS_DCF77
if (second(t) == DCF77_FRAME_SIZE - 1) // is it time to load new frame?
DCFpulse = DCF77_Frame(t1(t)); // generate next frame
if (DCFpulse[DCF77_FRAME_SIZE] !=
minute(t1(t))) // have recent frame? (timepulses could be missed!)
continue;
else
// DCF77_Pulse(t2(t), DCFpulse); // then output next second of this frame
DCF77_Pulse(t, DCFpulse); // then output next second of this frame
#endif
} // for
} // clock_loop()
#endif // HAS_IF482 || defined HAS_DCF77