timekeeper fixes (still experimental)
This commit is contained in:
		
							parent
							
								
									55e0c73c77
								
							
						
					
					
						commit
						7e4a360bb7
					
				@ -5,7 +5,6 @@
 | 
				
			|||||||
#include "cyclic.h"
 | 
					#include "cyclic.h"
 | 
				
			||||||
 | 
					
 | 
				
			||||||
extern uint8_t DisplayState;
 | 
					extern uint8_t DisplayState;
 | 
				
			||||||
extern timesource_t timeSource;
 | 
					 | 
				
			||||||
 | 
					
 | 
				
			||||||
extern HAS_DISPLAY u8x8;
 | 
					extern HAS_DISPLAY u8x8;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
				
			|||||||
@ -41,13 +41,13 @@
 | 
				
			|||||||
#define SCREEN_MODE (0x80)
 | 
					#define SCREEN_MODE (0x80)
 | 
				
			||||||
 | 
					
 | 
				
			||||||
// I2C bus access control
 | 
					// I2C bus access control
 | 
				
			||||||
#define I2C_MUTEX_LOCK()
 | 
					#define I2C_MUTEX_LOCK()                                                       \
 | 
				
			||||||
xSemaphoreTake(I2Caccess,
 | 
					  xSemaphoreTake(I2Caccess, (3 * DISPLAYREFRESH_MS / portTICK_PERIOD_MS)) ==   \
 | 
				
			||||||
               (3 * DISPLAYREFRESH_MS / portTICK_PERIOD_MS)) == pdTRUE
 | 
					      pdTRUE
 | 
				
			||||||
#define I2C_MUTEX_UNLOCK() xSemaphoreGive(I2Caccess)
 | 
					#define I2C_MUTEX_UNLOCK() xSemaphoreGive(I2Caccess)
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    // Struct holding devices's runtime configuration
 | 
					// Struct holding devices's runtime configuration
 | 
				
			||||||
    typedef struct {
 | 
					typedef struct {
 | 
				
			||||||
  uint8_t lorasf;      // 7-12, lora spreadfactor
 | 
					  uint8_t lorasf;      // 7-12, lora spreadfactor
 | 
				
			||||||
  uint8_t txpower;     // 2-15, lora tx power
 | 
					  uint8_t txpower;     // 2-15, lora tx power
 | 
				
			||||||
  uint8_t adrmode;     // 0=disabled, 1=enabled
 | 
					  uint8_t adrmode;     // 0=disabled, 1=enabled
 | 
				
			||||||
@ -108,8 +108,8 @@ 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; // one-pulse-per-second flags set by GPS or
 | 
					extern bool volatile TimePulseTick; // 1sec pps flag set by GPS or RTC
 | 
				
			||||||
                                    // RTC
 | 
					extern timesource_t timeSource;
 | 
				
			||||||
extern hw_timer_t *sendCycle, *displaytimer, *clockCycle;
 | 
					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;
 | 
				
			||||||
 | 
				
			|||||||
@ -9,10 +9,14 @@
 | 
				
			|||||||
#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);
 | 
				
			||||||
 | 
				
			|||||||
@ -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();
 | 
				
			||||||
 | 
				
			|||||||
@ -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
 | 
				
			||||||
 | 
				
			|||||||
@ -18,7 +18,7 @@ extern const char timeSetSymbols[];
 | 
				
			|||||||
void IRAM_ATTR CLOCKIRQ(void);
 | 
					void IRAM_ATTR CLOCKIRQ(void);
 | 
				
			||||||
void clock_init(void);
 | 
					void clock_init(void);
 | 
				
			||||||
void clock_loop(void *pvParameters);
 | 
					void clock_loop(void *pvParameters);
 | 
				
			||||||
time_t time_sync(void);
 | 
					void timeSync(void);
 | 
				
			||||||
void timepulse_start(void);
 | 
					void timepulse_start(void);
 | 
				
			||||||
uint8_t timepulse_init(void);
 | 
					uint8_t timepulse_init(void);
 | 
				
			||||||
time_t TimeIsValid(time_t const t);
 | 
					time_t TimeIsValid(time_t const t);
 | 
				
			||||||
 | 
				
			|||||||
@ -5,7 +5,7 @@
 | 
				
			|||||||
#include "cyclic.h"
 | 
					#include "cyclic.h"
 | 
				
			||||||
 | 
					
 | 
				
			||||||
// Local logging tag
 | 
					// Local logging tag
 | 
				
			||||||
static const char TAG[] = "main";
 | 
					static const char TAG[] = __FILE__;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
// do all housekeeping
 | 
					// do all housekeeping
 | 
				
			||||||
void doHousekeeping() {
 | 
					void doHousekeeping() {
 | 
				
			||||||
@ -17,8 +17,12 @@ 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();
 | 
				
			||||||
 | 
					#endif
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  // task storage debugging //
 | 
					  // task storage debugging //
 | 
				
			||||||
  ESP_LOGD(TAG, "IRQhandler %d bytes left | Taskstate = %d",
 | 
					  ESP_LOGD(TAG, "IRQhandler %d bytes left | Taskstate = %d",
 | 
				
			||||||
 | 
				
			|||||||
@ -14,7 +14,7 @@ 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__;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
// 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(time_t t, uint8_t const *DCFpulse) {
 | 
				
			||||||
 | 
				
			|||||||
@ -46,7 +46,6 @@ const char *printmonth[] = {"xxx", "Jan", "Feb", "Mar", "Apr", "May", "Jun",
 | 
				
			|||||||
                            "Jul", "Aug", "Sep", "Oct", "Nov", "Dec"};
 | 
					                            "Jul", "Aug", "Sep", "Oct", "Nov", "Dec"};
 | 
				
			||||||
 | 
					
 | 
				
			||||||
uint8_t DisplayState = 0;
 | 
					uint8_t DisplayState = 0;
 | 
				
			||||||
timesource_t timeSource = _unsynced;
 | 
					 | 
				
			||||||
 | 
					
 | 
				
			||||||
// 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) {
 | 
				
			||||||
 | 
				
			|||||||
@ -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");
 | 
				
			||||||
@ -76,20 +87,12 @@ void gps_read() {
 | 
				
			|||||||
// function to fetch current time from gps
 | 
					// function to fetch current time from gps
 | 
				
			||||||
time_t get_gpstime(void) {
 | 
					time_t get_gpstime(void) {
 | 
				
			||||||
 | 
					
 | 
				
			||||||
#define NMEA_FRAME_SIZE 80 // NEMA has a maxium of 80 bytes per record
 | 
					  // set time to wait for arrive next recent NMEA time record
 | 
				
			||||||
#define NMEA_BUFFER 50     // 50ms safety time regardless
 | 
					  static const uint32_t gpsDelay_ms = gpsDelay_ticks / portTICK_PERIOD_MS;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  time_t t = 0;
 | 
					  time_t t = 0;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
// set timeout for reading recent time from GPS
 | 
					  if ((gps.time.age() < gpsDelay_ms) && (gps.time.isValid())) {
 | 
				
			||||||
#ifdef GPS_SERIAL // serial GPS
 | 
					 | 
				
			||||||
  static const TickType_t txDelay =
 | 
					 | 
				
			||||||
      pdMS_TO_TICKS(1000 - NMEA_BUFFER - tx_Ticks(NMEA_FRAME_SIZE, GPS_SERIAL));
 | 
					 | 
				
			||||||
#else // I2C GPS
 | 
					 | 
				
			||||||
  static const TickType_t txDelay = 1000 - NMEA_BUFFER;
 | 
					 | 
				
			||||||
#endif
 | 
					 | 
				
			||||||
 | 
					 | 
				
			||||||
  if ((gps.time.age() < txDelay) && (gps.time.isValid())) {
 | 
					 | 
				
			||||||
 | 
					
 | 
				
			||||||
    ESP_LOGD(TAG, "GPS time age: %dms, is valid: %s", gps.time.age(),
 | 
					    ESP_LOGD(TAG, "GPS time age: %dms, is valid: %s", gps.time.age(),
 | 
				
			||||||
             gps.time.isValid() ? "yes" : "no");
 | 
					             gps.time.isValid() ? "yes" : "no");
 | 
				
			||||||
 | 
				
			|||||||
@ -82,19 +82,19 @@ 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) {
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  static const TickType_t txDelay =
 | 
					  static const TickType_t txDelay =
 | 
				
			||||||
      pdMS_TO_TICKS(IF482_PULSE_LENGTH - tx_Ticks(IF482_FRAME_SIZE, HAS_IF482));
 | 
					      pdMS_TO_TICKS(IF482_PULSE_LENGTH - tx_Ticks(IF482_FRAME_SIZE, HAS_IF482));
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  TickType_t startTime = xTaskGetTickCount();
 | 
					  //TickType_t startTime = xTaskGetTickCount();
 | 
				
			||||||
 | 
					  //vTaskDelayUntil(&startTime, txDelay); // wait until moment to fire
 | 
				
			||||||
  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
 | 
					  IF482.print(IF482_Frame(t + 1)); // note: if482 telegram for *next* second
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
				
			|||||||
@ -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,11 +12,10 @@ 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
 | 
					 | 
				
			||||||
 | 
					
 | 
				
			||||||
// button pressed?
 | 
					// button pressed?
 | 
				
			||||||
#ifdef HAS_BUTTON
 | 
					#ifdef HAS_BUTTON
 | 
				
			||||||
@ -31,8 +30,10 @@ void irqHandler(void *pvParameters) {
 | 
				
			|||||||
#endif
 | 
					#endif
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    // are cyclic tasks due?
 | 
					    // are cyclic tasks due?
 | 
				
			||||||
    if (InterruptStatus & CYCLIC_IRQ)
 | 
					    if (InterruptStatus & CYCLIC_IRQ) {
 | 
				
			||||||
      doHousekeeping();
 | 
					      doHousekeeping();
 | 
				
			||||||
 | 
					      timeSync();
 | 
				
			||||||
 | 
					    }
 | 
				
			||||||
 | 
					
 | 
				
			||||||
    // is time to send the payload?
 | 
					    // is time to send the payload?
 | 
				
			||||||
    if (InterruptStatus & SENDCOUNTER_IRQ)
 | 
					    if (InterruptStatus & SENDCOUNTER_IRQ)
 | 
				
			||||||
 | 
				
			|||||||
@ -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
 | 
				
			||||||
  time_t *pUserUTCTime = (time_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) {
 | 
				
			||||||
@ -473,11 +465,12 @@ void user_request_network_time_callback(void *pVoidUserUTCTime,
 | 
				
			|||||||
 | 
					
 | 
				
			||||||
  // Update system time with time read from the network
 | 
					  // Update system time with time read from the network
 | 
				
			||||||
  if (TimeIsValid(*pUserUTCTime)) {
 | 
					  if (TimeIsValid(*pUserUTCTime)) {
 | 
				
			||||||
    setTime(*pUserUTCTime);
 | 
					    xSemaphoreTake(TimePulse, pdMS_TO_TICKS(1000)); // wait for pps
 | 
				
			||||||
 | 
					    setTime(*pUserUTCTime + 1);
 | 
				
			||||||
    timeSource = _lora;
 | 
					    timeSource = _lora;
 | 
				
			||||||
    ESP_LOGI(TAG, "Received recent time from LoRa");
 | 
					    ESP_LOGI(TAG, "Received recent time from LoRa");
 | 
				
			||||||
    }
 | 
					  } else
 | 
				
			||||||
  else
 | 
					 | 
				
			||||||
    ESP_LOGI(TAG, "Invalid time received from 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
 | 
				
			||||||
							
								
								
									
										14
									
								
								src/main.cpp
									
									
									
									
									
								
							
							
						
						
									
										14
									
								
								src/main.cpp
									
									
									
									
									
								
							@ -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
 | 
				
			||||||
 | 
					
 | 
				
			||||||
*/
 | 
					*/
 | 
				
			||||||
 | 
					
 | 
				
			||||||
@ -72,6 +72,7 @@ TaskHandle_t irqHandlerTask, ClockTask;
 | 
				
			|||||||
SemaphoreHandle_t I2Caccess, TimePulse;
 | 
					SemaphoreHandle_t I2Caccess, TimePulse;
 | 
				
			||||||
bool volatile TimePulseTick = false;
 | 
					bool volatile TimePulseTick = false;
 | 
				
			||||||
time_t userUTCTime = 0;
 | 
					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
 | 
				
			||||||
@ -86,7 +87,7 @@ 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() {
 | 
				
			||||||
 | 
					
 | 
				
			||||||
@ -283,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");
 | 
				
			||||||
@ -361,10 +362,7 @@ void setup() {
 | 
				
			|||||||
  ESP_LOGI(TAG, "Starting Timekeeper...");
 | 
					  ESP_LOGI(TAG, "Starting Timekeeper...");
 | 
				
			||||||
  assert(timepulse_init()); // setup timepulse
 | 
					  assert(timepulse_init()); // setup timepulse
 | 
				
			||||||
  timepulse_start();
 | 
					  timepulse_start();
 | 
				
			||||||
#ifdef TIME_SYNC_INTERVAL
 | 
					  timeSync();
 | 
				
			||||||
  setSyncInterval(TIME_SYNC_INTERVAL * 60); // controls timeStatus() via Time.h
 | 
					 | 
				
			||||||
  setSyncProvider(time_sync); // is called by Time.h
 | 
					 | 
				
			||||||
#endif
 | 
					 | 
				
			||||||
 | 
					
 | 
				
			||||||
  // 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...");
 | 
				
			||||||
 | 
				
			|||||||
@ -1,7 +1,7 @@
 | 
				
			|||||||
#include "rtctime.h"
 | 
					#include "rtctime.h"
 | 
				
			||||||
 | 
					
 | 
				
			||||||
// Local logging tag
 | 
					// Local logging tag
 | 
				
			||||||
static const char TAG[] = "main";
 | 
					static const char TAG[] = __FILE__;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
#ifdef HAS_RTC // we have hardware RTC
 | 
					#ifdef HAS_RTC // we have hardware RTC
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
				
			|||||||
@ -1,57 +1,64 @@
 | 
				
			|||||||
#include "timekeeper.h"
 | 
					#include "timekeeper.h"
 | 
				
			||||||
 | 
					
 | 
				
			||||||
// Local logging tag
 | 
					// Local logging tag
 | 
				
			||||||
static const char TAG[] = "main";
 | 
					static const char TAG[] = __FILE__;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
// symbol to display current time source
 | 
					// symbol to display current time source
 | 
				
			||||||
const char timeSetSymbols[] = {'G', 'R', 'L', '?'};
 | 
					const char timeSetSymbols[] = {'G', 'R', 'L', '?'};
 | 
				
			||||||
 | 
					
 | 
				
			||||||
getExternalTime TimeSourcePtr; // pointer to time source function
 | 
					getExternalTime TimeSourcePtr; // pointer to time source function
 | 
				
			||||||
 | 
					
 | 
				
			||||||
time_t time_sync() {
 | 
					
 | 
				
			||||||
  // check synchonization of systime, called by cyclic.cpp
 | 
					// syncs systime from external time source and sets/reads RTC, called by
 | 
				
			||||||
 | 
					// cyclic.cpp
 | 
				
			||||||
 | 
					void timeSync(void) {
 | 
				
			||||||
 | 
					
 | 
				
			||||||
  time_t t = 0;
 | 
					  time_t t = 0;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
#ifdef HAS_GPS
 | 
					#ifdef HAS_GPS
 | 
				
			||||||
  xSemaphoreTake(TimePulse, pdMS_TO_TICKS(1000)); // wait for pps
 | 
					    // do we have a valid GPS time?
 | 
				
			||||||
  ESP_LOGD(TAG, "micros = %d", micros());
 | 
					    if (get_gpstime()) { // then let's sync GPS time on top of second
 | 
				
			||||||
  t = get_gpstime();
 | 
					
 | 
				
			||||||
  if (t) {
 | 
					      xSemaphoreTake(TimePulse, pdMS_TO_TICKS(1000)); // wait for pps
 | 
				
			||||||
    t++; // gps time concerns past second, so we add one second
 | 
					      vTaskDelay(gpsDelay_ticks);
 | 
				
			||||||
 | 
					      t = get_gpstime(); // fetch time from recent NEMA record
 | 
				
			||||||
 | 
					      if (t) {
 | 
				
			||||||
 | 
					        t++; // gps time concerns past second, so we add one
 | 
				
			||||||
 | 
					        xSemaphoreTake(TimePulse, pdMS_TO_TICKS(1000)); // wait for pps
 | 
				
			||||||
 | 
					        setTime(t);
 | 
				
			||||||
#ifdef HAS_RTC
 | 
					#ifdef HAS_RTC
 | 
				
			||||||
    set_rtctime(t); // calibrate RTC
 | 
					        set_rtctime(t); // calibrate RTC
 | 
				
			||||||
#endif
 | 
					#endif
 | 
				
			||||||
    timeSource = _gps;
 | 
					        timeSource = _gps;
 | 
				
			||||||
    goto exit;
 | 
					        goto exit;
 | 
				
			||||||
  }
 | 
					      }
 | 
				
			||||||
 | 
					    }
 | 
				
			||||||
#endif
 | 
					#endif
 | 
				
			||||||
 | 
					
 | 
				
			||||||
// no GPS -> fallback to RTC time while trying lora sync
 | 
					// no GPS -> fallback to RTC time while trying lora sync
 | 
				
			||||||
#ifdef HAS_RTC
 | 
					#ifdef HAS_RTC
 | 
				
			||||||
  t = get_rtctime();
 | 
					    t = get_rtctime();
 | 
				
			||||||
  if (t)
 | 
					    if (t) {
 | 
				
			||||||
    timeSource = _rtc;
 | 
					      setTime(t);
 | 
				
			||||||
  else
 | 
					      timeSource = _rtc;
 | 
				
			||||||
    ESP_LOGW(TAG, "no confident RTC time");
 | 
					    } else
 | 
				
			||||||
 | 
					      ESP_LOGW(TAG, "no confident RTC time");
 | 
				
			||||||
#endif
 | 
					#endif
 | 
				
			||||||
 | 
					
 | 
				
			||||||
// try lora sync if we have
 | 
					// try lora sync if we have
 | 
				
			||||||
#if defined HAS_LORA && defined TIME_SYNC_LORA
 | 
					#if defined HAS_LORA && defined TIME_SYNC_LORA
 | 
				
			||||||
  LMIC_requestNetworkTime(user_request_network_time_callback, &userUTCTime);
 | 
					    LMIC_requestNetworkTime(user_request_network_time_callback, &userUTCTime);
 | 
				
			||||||
#endif
 | 
					#endif
 | 
				
			||||||
 | 
					
 | 
				
			||||||
exit:
 | 
					exit:
 | 
				
			||||||
  ESP_LOGD(TAG, "micros = %d", micros());
 | 
					 | 
				
			||||||
  if (t)
 | 
					 | 
				
			||||||
    ESP_LOGD(TAG, "Time was set by %c to %02d:%02d:%02d",
 | 
					 | 
				
			||||||
             timeSetSymbols[timeSource], hour(t), minute(t), second(t));
 | 
					 | 
				
			||||||
  else
 | 
					 | 
				
			||||||
    timeSource = _unsynced;
 | 
					 | 
				
			||||||
 | 
					
 | 
				
			||||||
  return t;
 | 
					    if (t)
 | 
				
			||||||
 | 
					      ESP_LOGD(TAG, "Time was set by %c to %02d:%02d:%02d",
 | 
				
			||||||
 | 
					               timeSetSymbols[timeSource], hour(t), minute(t), second(t));
 | 
				
			||||||
 | 
					    else
 | 
				
			||||||
 | 
					      timeSource = _unsynced;
 | 
				
			||||||
 | 
					
 | 
				
			||||||
} // time_sync()
 | 
					} // timeSync()
 | 
				
			||||||
 | 
					
 | 
				
			||||||
// 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() {
 | 
				
			||||||
@ -119,8 +126,6 @@ void IRAM_ATTR CLOCKIRQ(void) {
 | 
				
			|||||||
// helper function to check plausibility of a time
 | 
					// helper function to check plausibility of a time
 | 
				
			||||||
time_t TimeIsValid(time_t const t) {
 | 
					time_t TimeIsValid(time_t const t) {
 | 
				
			||||||
  // is it a time in the past? we use compile date to guess
 | 
					  // is it a time in the past? we use compile date to guess
 | 
				
			||||||
  ESP_LOGD(TAG, "t=%d, tt=%d, valid: %s", t, compiledUTC(),
 | 
					 | 
				
			||||||
           (t >= compiledUTC()) ? "yes" : "no");
 | 
					 | 
				
			||||||
  return (t >= compiledUTC() ? t : 0);
 | 
					  return (t >= compiledUTC() ? t : 0);
 | 
				
			||||||
}
 | 
					}
 | 
				
			||||||
 | 
					
 | 
				
			||||||
 | 
				
			|||||||
		Loading…
	
		Reference in New Issue
	
	Block a user