Setting RTC to GPS with 1PPS precision working. Here is an example log:
20260217_200901_z set RTC to GPS using 1PPS pulse-per-second discipline rtc-gps drift=-28 s 20260217_201001_z set RTC to GPS using 1PPS pulse-per-second discipline rtc-gps drift=+0 s 20260217_201119_z set RTC to GPS using 1PPS pulse-per-second discipline rtc-gps drift=+0 s 20260217_201219_z set RTC to GPS using 1PPS pulse-per-second discipline rtc-gps drift=+0 s
This commit is contained in:
parent
21825c09c6
commit
5f5742f198
6 changed files with 1172 additions and 0 deletions
33
exercises/11_Set_RTC2GPS/README.md
Normal file
33
exercises/11_Set_RTC2GPS/README.md
Normal file
|
|
@ -0,0 +1,33 @@
|
|||
## Exercise 11: Set RTC to GPS (1PPS Discipline)
|
||||
|
||||
This exercise extends Exercise 9 behavior (GPS + SD + OLED) and disciplines the onboard RTC from GPS UTC using the GPS `1PPS` (pulse-per-second) timing signal.
|
||||
|
||||
Implemented behavior:
|
||||
|
||||
1. Boots PMU, OLED, SD watcher, and GPS UART using the same T-Beam Supreme pin mapping from prior exercises.
|
||||
2. Parses NMEA (`RMC`, `GGA`, `GSV`) to track UTC validity and satellite counts.
|
||||
3. Every 1 minute, attempts to set RTC from GPS:
|
||||
- Uses latest valid GPS UTC.
|
||||
- Waits for next `1PPS` rising edge.
|
||||
- Sets RTC to GPS time aligned to that edge (UTC + 1 second).
|
||||
4. Appends event records to SD file:
|
||||
- Path: `/gps/discipline_rtc.log`
|
||||
- Append-only writes (`FILE_APPEND`)
|
||||
- Format:
|
||||
- `YYYYMMDD_HH24MISS_z\t set RTC to GPS using 1PPS pulse-per-second discipline\trtc-gps drift=+/-Ns`
|
||||
5. OLED success message shows RTC disciplined confirmation and timestamp.
|
||||
6. If GPS time cannot be determined (or 1PPS edge is not seen in timeout), OLED shows failure status and the loop delays 30 seconds before retry.
|
||||
|
||||
## Build
|
||||
|
||||
```bash
|
||||
source /home/jlpoole/rnsenv/bin/activate
|
||||
pio run -e node_a
|
||||
```
|
||||
|
||||
## Upload
|
||||
|
||||
```bash
|
||||
source /home/jlpoole/rnsenv/bin/activate
|
||||
pio run -e node_a -t upload --upload-port /dev/ttyACM0
|
||||
```
|
||||
360
exercises/11_Set_RTC2GPS/lib/startup_sd/StartupSdManager.cpp
Normal file
360
exercises/11_Set_RTC2GPS/lib/startup_sd/StartupSdManager.cpp
Normal file
|
|
@ -0,0 +1,360 @@
|
|||
#include "StartupSdManager.h"
|
||||
|
||||
#include <stdarg.h>
|
||||
#include "driver/gpio.h"
|
||||
|
||||
StartupSdManager::StartupSdManager(Print& serial) : serial_(serial) {}
|
||||
|
||||
bool StartupSdManager::begin(const SdWatcherConfig& cfg, SdStatusCallback callback) {
|
||||
cfg_ = cfg;
|
||||
callback_ = callback;
|
||||
|
||||
forceSpiDeselected();
|
||||
dumpSdPins("very-early");
|
||||
|
||||
if (!initPmuForSdPower()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
cycleSdRail();
|
||||
delay(cfg_.startupWarmupMs);
|
||||
|
||||
bool warmMounted = false;
|
||||
for (uint8_t i = 0; i < 3; ++i) {
|
||||
if (mountPreferred(false)) {
|
||||
warmMounted = true;
|
||||
break;
|
||||
}
|
||||
delay(200);
|
||||
}
|
||||
|
||||
// Some cards need a longer power/settle window after cold boot.
|
||||
// Before declaring ABSENT, retry with extended settle and a full scan.
|
||||
if (!warmMounted) {
|
||||
logf("Watcher: startup preferred mount failed, retrying with extended settle");
|
||||
cycleSdRail(400, 1200);
|
||||
delay(cfg_.startupWarmupMs + 1500);
|
||||
warmMounted = mountCardFullScan();
|
||||
}
|
||||
|
||||
if (warmMounted) {
|
||||
setStateMounted();
|
||||
} else {
|
||||
setStateAbsent();
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
void StartupSdManager::update() {
|
||||
const uint32_t now = millis();
|
||||
const uint32_t pollInterval =
|
||||
(watchState_ == SdWatchState::MOUNTED) ? cfg_.pollIntervalMountedMs : cfg_.pollIntervalAbsentMs;
|
||||
|
||||
if ((uint32_t)(now - lastPollMs_) < pollInterval) {
|
||||
return;
|
||||
}
|
||||
lastPollMs_ = now;
|
||||
|
||||
if (watchState_ == SdWatchState::MOUNTED) {
|
||||
if (verifyMountedCard()) {
|
||||
presentVotes_ = 0;
|
||||
absentVotes_ = 0;
|
||||
return;
|
||||
}
|
||||
|
||||
if (mountPreferred(false) && verifyMountedCard()) {
|
||||
presentVotes_ = 0;
|
||||
absentVotes_ = 0;
|
||||
return;
|
||||
}
|
||||
|
||||
absentVotes_++;
|
||||
presentVotes_ = 0;
|
||||
if (absentVotes_ >= cfg_.votesToAbsent) {
|
||||
setStateAbsent();
|
||||
absentVotes_ = 0;
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
bool mounted = mountPreferred(false);
|
||||
if (!mounted && (uint32_t)(now - lastFullScanMs_) >= cfg_.fullScanIntervalMs) {
|
||||
lastFullScanMs_ = now;
|
||||
if (cfg_.recoveryRailCycleOnFullScan) {
|
||||
logf("Watcher: recovery rail cycle before full scan");
|
||||
cycleSdRail(cfg_.recoveryRailOffMs, cfg_.recoveryRailOnSettleMs);
|
||||
delay(150);
|
||||
}
|
||||
logf("Watcher: preferred probe failed, running full scan");
|
||||
mounted = mountCardFullScan();
|
||||
}
|
||||
|
||||
if (mounted) {
|
||||
presentVotes_++;
|
||||
absentVotes_ = 0;
|
||||
if (presentVotes_ >= cfg_.votesToPresent) {
|
||||
setStateMounted();
|
||||
presentVotes_ = 0;
|
||||
}
|
||||
} else {
|
||||
absentVotes_++;
|
||||
presentVotes_ = 0;
|
||||
if (absentVotes_ >= cfg_.votesToAbsent) {
|
||||
setStateAbsent();
|
||||
absentVotes_ = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool StartupSdManager::consumeMountedEvent() {
|
||||
bool out = mountedEventPending_;
|
||||
mountedEventPending_ = false;
|
||||
return out;
|
||||
}
|
||||
|
||||
bool StartupSdManager::consumeRemovedEvent() {
|
||||
bool out = removedEventPending_;
|
||||
removedEventPending_ = false;
|
||||
return out;
|
||||
}
|
||||
|
||||
void StartupSdManager::logf(const char* fmt, ...) {
|
||||
char msg[196];
|
||||
va_list args;
|
||||
va_start(args, fmt);
|
||||
vsnprintf(msg, sizeof(msg), fmt, args);
|
||||
va_end(args);
|
||||
serial_.printf("[%10lu][%06lu] %s\r\n",
|
||||
(unsigned long)millis(),
|
||||
(unsigned long)logSeq_++,
|
||||
msg);
|
||||
}
|
||||
|
||||
void StartupSdManager::notify(SdEvent event, const char* message) {
|
||||
if (callback_ != nullptr) {
|
||||
callback_(event, message);
|
||||
}
|
||||
}
|
||||
|
||||
void StartupSdManager::forceSpiDeselected() {
|
||||
pinMode(tbeam_supreme::sdCs(), OUTPUT);
|
||||
digitalWrite(tbeam_supreme::sdCs(), HIGH);
|
||||
pinMode(tbeam_supreme::imuCs(), OUTPUT);
|
||||
digitalWrite(tbeam_supreme::imuCs(), HIGH);
|
||||
}
|
||||
|
||||
void StartupSdManager::dumpSdPins(const char* tag) {
|
||||
if (!cfg_.enablePinDumps) {
|
||||
(void)tag;
|
||||
return;
|
||||
}
|
||||
|
||||
const gpio_num_t cs = (gpio_num_t)tbeam_supreme::sdCs();
|
||||
const gpio_num_t sck = (gpio_num_t)tbeam_supreme::sdSck();
|
||||
const gpio_num_t miso = (gpio_num_t)tbeam_supreme::sdMiso();
|
||||
const gpio_num_t mosi = (gpio_num_t)tbeam_supreme::sdMosi();
|
||||
logf("PINS(%s): CS=%d SCK=%d MISO=%d MOSI=%d",
|
||||
tag, gpio_get_level(cs), gpio_get_level(sck), gpio_get_level(miso), gpio_get_level(mosi));
|
||||
}
|
||||
|
||||
bool StartupSdManager::initPmuForSdPower() {
|
||||
if (!tbeam_supreme::initPmuForPeripherals(pmu_, &serial_)) {
|
||||
logf("ERROR: PMU init failed");
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
void StartupSdManager::cycleSdRail(uint32_t offMs, uint32_t onSettleMs) {
|
||||
if (!cfg_.enableSdRailCycle) {
|
||||
return;
|
||||
}
|
||||
if (!pmu_) {
|
||||
logf("SD rail cycle skipped: pmu=null");
|
||||
return;
|
||||
}
|
||||
|
||||
forceSpiDeselected();
|
||||
pmu_->disablePowerOutput(XPOWERS_BLDO1);
|
||||
delay(offMs);
|
||||
pmu_->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
|
||||
pmu_->enablePowerOutput(XPOWERS_BLDO1);
|
||||
delay(onSettleMs);
|
||||
}
|
||||
|
||||
bool StartupSdManager::tryMountWithBus(SPIClass& bus, const char* busName, uint32_t hz, bool verbose) {
|
||||
SD.end();
|
||||
bus.end();
|
||||
delay(10);
|
||||
forceSpiDeselected();
|
||||
|
||||
bus.begin(tbeam_supreme::sdSck(), tbeam_supreme::sdMiso(), tbeam_supreme::sdMosi(), tbeam_supreme::sdCs());
|
||||
digitalWrite(tbeam_supreme::sdCs(), HIGH);
|
||||
delay(2);
|
||||
for (int i = 0; i < 10; i++) {
|
||||
bus.transfer(0xFF);
|
||||
}
|
||||
delay(2);
|
||||
|
||||
if (verbose) {
|
||||
logf("SD: trying bus=%s freq=%lu Hz", busName, (unsigned long)hz);
|
||||
}
|
||||
|
||||
if (!SD.begin(tbeam_supreme::sdCs(), bus, hz)) {
|
||||
if (verbose) {
|
||||
logf("SD: mount failed (possible non-FAT format, power, or bus issue)");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
if (SD.cardType() == CARD_NONE) {
|
||||
SD.end();
|
||||
return false;
|
||||
}
|
||||
|
||||
sdSpi_ = &bus;
|
||||
sdBusName_ = busName;
|
||||
sdFreq_ = hz;
|
||||
return true;
|
||||
}
|
||||
|
||||
bool StartupSdManager::mountPreferred(bool verbose) {
|
||||
return tryMountWithBus(sdSpiH_, "HSPI", 400000, verbose);
|
||||
}
|
||||
|
||||
bool StartupSdManager::mountCardFullScan() {
|
||||
const uint32_t freqs[] = {400000, 1000000, 4000000, 10000000};
|
||||
|
||||
for (uint8_t i = 0; i < (sizeof(freqs) / sizeof(freqs[0])); ++i) {
|
||||
if (tryMountWithBus(sdSpiH_, "HSPI", freqs[i], true)) {
|
||||
logf("SD: card detected and mounted");
|
||||
return true;
|
||||
}
|
||||
}
|
||||
for (uint8_t i = 0; i < (sizeof(freqs) / sizeof(freqs[0])); ++i) {
|
||||
if (tryMountWithBus(sdSpiF_, "FSPI", freqs[i], true)) {
|
||||
logf("SD: card detected and mounted");
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
logf("SD: begin() failed on all bus/frequency attempts");
|
||||
return false;
|
||||
}
|
||||
|
||||
bool StartupSdManager::verifyMountedCard() {
|
||||
File root = SD.open("/", FILE_READ);
|
||||
if (!root) {
|
||||
return false;
|
||||
}
|
||||
root.close();
|
||||
return true;
|
||||
}
|
||||
|
||||
const char* StartupSdManager::cardTypeToString(uint8_t type) {
|
||||
switch (type) {
|
||||
case CARD_MMC:
|
||||
return "MMC";
|
||||
case CARD_SD:
|
||||
return "SDSC";
|
||||
case CARD_SDHC:
|
||||
return "SDHC/SDXC";
|
||||
default:
|
||||
return "UNKNOWN";
|
||||
}
|
||||
}
|
||||
|
||||
void StartupSdManager::printCardInfo() {
|
||||
uint8_t cardType = SD.cardType();
|
||||
uint64_t cardSizeMB = SD.cardSize() / (1024ULL * 1024ULL);
|
||||
uint64_t totalMB = SD.totalBytes() / (1024ULL * 1024ULL);
|
||||
uint64_t usedMB = SD.usedBytes() / (1024ULL * 1024ULL);
|
||||
|
||||
logf("SD type: %s", cardTypeToString(cardType));
|
||||
logf("SD size: %llu MB", cardSizeMB);
|
||||
logf("FS total: %llu MB", totalMB);
|
||||
logf("FS used : %llu MB", usedMB);
|
||||
logf("SPI bus: %s @ %lu Hz", sdBusName_, (unsigned long)sdFreq_);
|
||||
}
|
||||
|
||||
bool StartupSdManager::ensureDirRecursive(const char* path) {
|
||||
String full(path);
|
||||
if (!full.startsWith("/")) {
|
||||
full = "/" + full;
|
||||
}
|
||||
|
||||
int start = 1;
|
||||
while (start > 0 && start < (int)full.length()) {
|
||||
int slash = full.indexOf('/', start);
|
||||
String partial = (slash < 0) ? full : full.substring(0, slash);
|
||||
if (!SD.exists(partial.c_str()) && !SD.mkdir(partial.c_str())) {
|
||||
logf("ERROR: mkdir failed for %s", partial.c_str());
|
||||
return false;
|
||||
}
|
||||
if (slash < 0) {
|
||||
break;
|
||||
}
|
||||
start = slash + 1;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool StartupSdManager::rewriteFile(const char* path, const char* payload) {
|
||||
if (SD.exists(path) && !SD.remove(path)) {
|
||||
logf("ERROR: failed to erase %s", path);
|
||||
return false;
|
||||
}
|
||||
|
||||
File f = SD.open(path, FILE_WRITE);
|
||||
if (!f) {
|
||||
logf("ERROR: failed to create %s", path);
|
||||
return false;
|
||||
}
|
||||
|
||||
size_t wrote = f.println(payload);
|
||||
f.close();
|
||||
if (wrote == 0) {
|
||||
logf("ERROR: write failed for %s", path);
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
void StartupSdManager::permissionsDemo(const char* path) {
|
||||
logf("Permissions demo: FAT has no Unix chmod/chown, use open mode only.");
|
||||
File r = SD.open(path, FILE_READ);
|
||||
if (!r) {
|
||||
logf("Could not open %s as FILE_READ", path);
|
||||
return;
|
||||
}
|
||||
size_t writeInReadMode = r.print("attempt write while opened read-only");
|
||||
if (writeInReadMode == 0) {
|
||||
logf("As expected, FILE_READ write was blocked.");
|
||||
} else {
|
||||
logf("NOTE: FILE_READ write returned %u (unexpected)", (unsigned)writeInReadMode);
|
||||
}
|
||||
r.close();
|
||||
}
|
||||
|
||||
void StartupSdManager::setStateMounted() {
|
||||
if (watchState_ != SdWatchState::MOUNTED) {
|
||||
logf("EVENT: card inserted/mounted");
|
||||
mountedEventPending_ = true;
|
||||
notify(SdEvent::CARD_MOUNTED, "SD card mounted");
|
||||
}
|
||||
watchState_ = SdWatchState::MOUNTED;
|
||||
}
|
||||
|
||||
void StartupSdManager::setStateAbsent() {
|
||||
if (watchState_ == SdWatchState::MOUNTED) {
|
||||
logf("EVENT: card removed/unavailable");
|
||||
removedEventPending_ = true;
|
||||
notify(SdEvent::CARD_REMOVED, "SD card removed");
|
||||
} else if (watchState_ != SdWatchState::ABSENT) {
|
||||
logf("EVENT: no card detected");
|
||||
notify(SdEvent::NO_CARD, "Missing SD card or invalid FAT16/FAT32 format");
|
||||
}
|
||||
SD.end();
|
||||
watchState_ = SdWatchState::ABSENT;
|
||||
}
|
||||
90
exercises/11_Set_RTC2GPS/lib/startup_sd/StartupSdManager.h
Normal file
90
exercises/11_Set_RTC2GPS/lib/startup_sd/StartupSdManager.h
Normal file
|
|
@ -0,0 +1,90 @@
|
|||
#pragma once
|
||||
|
||||
#include <Arduino.h>
|
||||
#include <SD.h>
|
||||
#include <SPI.h>
|
||||
#include <Wire.h>
|
||||
#include "tbeam_supreme_adapter.h"
|
||||
|
||||
enum class SdWatchState : uint8_t {
|
||||
UNKNOWN = 0,
|
||||
ABSENT,
|
||||
MOUNTED
|
||||
};
|
||||
|
||||
enum class SdEvent : uint8_t {
|
||||
NO_CARD,
|
||||
CARD_MOUNTED,
|
||||
CARD_REMOVED
|
||||
};
|
||||
|
||||
using SdStatusCallback = void (*)(SdEvent event, const char* message);
|
||||
|
||||
struct SdWatcherConfig {
|
||||
bool enableSdRailCycle = true;
|
||||
bool enablePinDumps = true;
|
||||
bool recoveryRailCycleOnFullScan = true;
|
||||
uint32_t recoveryRailOffMs = 250;
|
||||
uint32_t recoveryRailOnSettleMs = 700;
|
||||
uint32_t startupWarmupMs = 1500;
|
||||
uint32_t pollIntervalAbsentMs = 1000;
|
||||
uint32_t pollIntervalMountedMs = 2000;
|
||||
uint32_t fullScanIntervalMs = 10000;
|
||||
uint8_t votesToPresent = 2;
|
||||
uint8_t votesToAbsent = 5;
|
||||
};
|
||||
|
||||
class StartupSdManager {
|
||||
public:
|
||||
explicit StartupSdManager(Print& serial = Serial);
|
||||
|
||||
bool begin(const SdWatcherConfig& cfg, SdStatusCallback callback = nullptr);
|
||||
void update();
|
||||
|
||||
bool isMounted() const { return watchState_ == SdWatchState::MOUNTED; }
|
||||
SdWatchState state() const { return watchState_; }
|
||||
|
||||
bool consumeMountedEvent();
|
||||
bool consumeRemovedEvent();
|
||||
|
||||
void printCardInfo();
|
||||
bool ensureDirRecursive(const char* path);
|
||||
bool rewriteFile(const char* path, const char* payload);
|
||||
void permissionsDemo(const char* path);
|
||||
|
||||
private:
|
||||
void logf(const char* fmt, ...);
|
||||
void notify(SdEvent event, const char* message);
|
||||
void forceSpiDeselected();
|
||||
void dumpSdPins(const char* tag);
|
||||
bool initPmuForSdPower();
|
||||
void cycleSdRail(uint32_t offMs = 250, uint32_t onSettleMs = 600);
|
||||
bool tryMountWithBus(SPIClass& bus, const char* busName, uint32_t hz, bool verbose);
|
||||
bool mountPreferred(bool verbose);
|
||||
bool mountCardFullScan();
|
||||
bool verifyMountedCard();
|
||||
const char* cardTypeToString(uint8_t type);
|
||||
void setStateMounted();
|
||||
void setStateAbsent();
|
||||
|
||||
Print& serial_;
|
||||
SdWatcherConfig cfg_{};
|
||||
SdStatusCallback callback_ = nullptr;
|
||||
|
||||
SPIClass sdSpiH_{HSPI};
|
||||
SPIClass sdSpiF_{FSPI};
|
||||
SPIClass* sdSpi_ = nullptr;
|
||||
const char* sdBusName_ = "none";
|
||||
uint32_t sdFreq_ = 0;
|
||||
XPowersLibInterface* pmu_ = nullptr;
|
||||
|
||||
SdWatchState watchState_ = SdWatchState::UNKNOWN;
|
||||
uint8_t presentVotes_ = 0;
|
||||
uint8_t absentVotes_ = 0;
|
||||
uint32_t lastPollMs_ = 0;
|
||||
uint32_t lastFullScanMs_ = 0;
|
||||
uint32_t logSeq_ = 0;
|
||||
|
||||
bool mountedEventPending_ = false;
|
||||
bool removedEventPending_ = false;
|
||||
};
|
||||
12
exercises/11_Set_RTC2GPS/lib/startup_sd/library.json
Normal file
12
exercises/11_Set_RTC2GPS/lib/startup_sd/library.json
Normal file
|
|
@ -0,0 +1,12 @@
|
|||
{
|
||||
"name": "startup_sd",
|
||||
"version": "0.1.0",
|
||||
"dependencies": [
|
||||
{
|
||||
"name": "XPowersLib"
|
||||
},
|
||||
{
|
||||
"name": "Wire"
|
||||
}
|
||||
]
|
||||
}
|
||||
41
exercises/11_Set_RTC2GPS/platformio.ini
Normal file
41
exercises/11_Set_RTC2GPS/platformio.ini
Normal file
|
|
@ -0,0 +1,41 @@
|
|||
; 20260213 ChatGPT
|
||||
; $Id$
|
||||
; $HeadURL$
|
||||
|
||||
[platformio]
|
||||
default_envs = node_a
|
||||
|
||||
[env]
|
||||
platform = espressif32
|
||||
framework = arduino
|
||||
board = esp32-s3-devkitc-1
|
||||
monitor_speed = 115200
|
||||
lib_deps =
|
||||
lewisxhe/XPowersLib@0.3.3
|
||||
Wire
|
||||
olikraus/U8g2@^2.36.4
|
||||
|
||||
; SD pins based on T-Beam S3 core pin mapping
|
||||
build_flags =
|
||||
-I ../../shared/boards
|
||||
-I ../../external/microReticulum_Firmware
|
||||
-D BOARD_MODEL=BOARD_TBEAM_S_V1
|
||||
-D OLED_SDA=17
|
||||
-D OLED_SCL=18
|
||||
-D OLED_ADDR=0x3C
|
||||
-D GPS_RX_PIN=9
|
||||
-D GPS_TX_PIN=8
|
||||
-D GPS_WAKEUP_PIN=7
|
||||
-D GPS_1PPS_PIN=6
|
||||
-D ARDUINO_USB_MODE=1
|
||||
-D ARDUINO_USB_CDC_ON_BOOT=1
|
||||
|
||||
[env:node_a]
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D NODE_LABEL=\"A\"
|
||||
|
||||
[env:node_b]
|
||||
build_flags =
|
||||
${env.build_flags}
|
||||
-D NODE_LABEL=\"B\"
|
||||
636
exercises/11_Set_RTC2GPS/src/main.cpp
Normal file
636
exercises/11_Set_RTC2GPS/src/main.cpp
Normal file
|
|
@ -0,0 +1,636 @@
|
|||
// 20260217 ChatGPT
|
||||
// $Id$
|
||||
// $HeadURL$
|
||||
|
||||
#include <Arduino.h>
|
||||
#include <Wire.h>
|
||||
#include <SD.h>
|
||||
#include <U8g2lib.h>
|
||||
|
||||
#include "StartupSdManager.h"
|
||||
#include "tbeam_supreme_adapter.h"
|
||||
|
||||
#ifndef OLED_SDA
|
||||
#define OLED_SDA 17
|
||||
#endif
|
||||
|
||||
#ifndef OLED_SCL
|
||||
#define OLED_SCL 18
|
||||
#endif
|
||||
|
||||
#ifndef OLED_ADDR
|
||||
#define OLED_ADDR 0x3C
|
||||
#endif
|
||||
|
||||
#ifndef RTC_I2C_ADDR
|
||||
#define RTC_I2C_ADDR 0x51
|
||||
#endif
|
||||
|
||||
#ifndef GPS_BAUD
|
||||
#define GPS_BAUD 9600
|
||||
#endif
|
||||
|
||||
#ifndef FILE_APPEND
|
||||
#define FILE_APPEND FILE_WRITE
|
||||
#endif
|
||||
|
||||
static const uint32_t kSerialDelayMs = 5000;
|
||||
static const uint32_t kLoopMsDiscipline = 60000;
|
||||
static const uint32_t kNoTimeDelayMs = 30000;
|
||||
static const uint32_t kGpsStartupProbeMs = 20000;
|
||||
static const uint32_t kPpsWaitTimeoutMs = 1500;
|
||||
|
||||
static XPowersLibInterface* g_pmu = nullptr;
|
||||
static StartupSdManager g_sd(Serial);
|
||||
static U8G2_SH1106_128X64_NONAME_F_HW_I2C g_oled(U8G2_R0, /* reset=*/U8X8_PIN_NONE);
|
||||
static HardwareSerial g_gpsSerial(1);
|
||||
|
||||
static uint32_t g_logSeq = 0;
|
||||
static uint32_t g_nextDisciplineMs = 0;
|
||||
static bool g_gpsPathReady = false;
|
||||
|
||||
static char g_gpsLine[128];
|
||||
static size_t g_gpsLineLen = 0;
|
||||
|
||||
static volatile uint32_t g_ppsEdgeCount = 0;
|
||||
|
||||
struct DateTime {
|
||||
uint16_t year;
|
||||
uint8_t month;
|
||||
uint8_t day;
|
||||
uint8_t hour;
|
||||
uint8_t minute;
|
||||
uint8_t second;
|
||||
};
|
||||
|
||||
struct GpsState {
|
||||
bool sawAnySentence = false;
|
||||
bool hasValidUtc = false;
|
||||
uint8_t satsUsed = 0;
|
||||
uint8_t satsInView = 0;
|
||||
DateTime utc{};
|
||||
uint32_t lastUtcMs = 0;
|
||||
};
|
||||
|
||||
static GpsState g_gps;
|
||||
|
||||
static void logf(const char* fmt, ...) {
|
||||
char msg[240];
|
||||
va_list args;
|
||||
va_start(args, fmt);
|
||||
vsnprintf(msg, sizeof(msg), fmt, args);
|
||||
va_end(args);
|
||||
Serial.printf("[%10lu][%06lu] %s\r\n", (unsigned long)millis(), (unsigned long)g_logSeq++, msg);
|
||||
}
|
||||
|
||||
static void oledShowLines(const char* l1,
|
||||
const char* l2 = nullptr,
|
||||
const char* l3 = nullptr,
|
||||
const char* l4 = nullptr,
|
||||
const char* l5 = nullptr) {
|
||||
g_oled.clearBuffer();
|
||||
g_oled.setFont(u8g2_font_5x8_tf);
|
||||
if (l1) g_oled.drawUTF8(0, 12, l1);
|
||||
if (l2) g_oled.drawUTF8(0, 24, l2);
|
||||
if (l3) g_oled.drawUTF8(0, 36, l3);
|
||||
if (l4) g_oled.drawUTF8(0, 48, l4);
|
||||
if (l5) g_oled.drawUTF8(0, 60, l5);
|
||||
g_oled.sendBuffer();
|
||||
}
|
||||
|
||||
static uint8_t toBcd(uint8_t v) {
|
||||
return (uint8_t)(((v / 10U) << 4U) | (v % 10U));
|
||||
}
|
||||
|
||||
static uint8_t fromBcd(uint8_t b) {
|
||||
return (uint8_t)(((b >> 4U) * 10U) + (b & 0x0FU));
|
||||
}
|
||||
|
||||
static bool rtcRead(DateTime& out, bool& lowVoltageFlag) {
|
||||
Wire1.beginTransmission(RTC_I2C_ADDR);
|
||||
Wire1.write(0x02);
|
||||
if (Wire1.endTransmission(false) != 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
const uint8_t need = 7;
|
||||
uint8_t got = Wire1.requestFrom((int)RTC_I2C_ADDR, (int)need);
|
||||
if (got != need) {
|
||||
return false;
|
||||
}
|
||||
|
||||
uint8_t sec = Wire1.read();
|
||||
uint8_t min = Wire1.read();
|
||||
uint8_t hour = Wire1.read();
|
||||
uint8_t day = Wire1.read();
|
||||
(void)Wire1.read();
|
||||
uint8_t month = Wire1.read();
|
||||
uint8_t year = Wire1.read();
|
||||
|
||||
lowVoltageFlag = (sec & 0x80U) != 0;
|
||||
out.second = fromBcd(sec & 0x7FU);
|
||||
out.minute = fromBcd(min & 0x7FU);
|
||||
out.hour = fromBcd(hour & 0x3FU);
|
||||
out.day = fromBcd(day & 0x3FU);
|
||||
out.month = fromBcd(month & 0x1FU);
|
||||
uint8_t yy = fromBcd(year);
|
||||
bool century = (month & 0x80U) != 0;
|
||||
out.year = century ? (1900U + yy) : (2000U + yy);
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool rtcWrite(const DateTime& dt) {
|
||||
Wire1.beginTransmission(RTC_I2C_ADDR);
|
||||
Wire1.write(0x02);
|
||||
Wire1.write(toBcd(dt.second & 0x7FU));
|
||||
Wire1.write(toBcd(dt.minute));
|
||||
Wire1.write(toBcd(dt.hour));
|
||||
Wire1.write(toBcd(dt.day));
|
||||
Wire1.write(0x00);
|
||||
|
||||
uint8_t monthReg = toBcd(dt.month);
|
||||
if (dt.year < 2000U) {
|
||||
monthReg |= 0x80U;
|
||||
}
|
||||
Wire1.write(monthReg);
|
||||
Wire1.write(toBcd((uint8_t)(dt.year % 100U)));
|
||||
|
||||
return Wire1.endTransmission() == 0;
|
||||
}
|
||||
|
||||
static bool isLeapYear(uint16_t y) {
|
||||
return ((y % 4U) == 0U && (y % 100U) != 0U) || ((y % 400U) == 0U);
|
||||
}
|
||||
|
||||
static uint8_t daysInMonth(uint16_t year, uint8_t month) {
|
||||
static const uint8_t kDays[12] = {31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31};
|
||||
if (month == 2) {
|
||||
return (uint8_t)(isLeapYear(year) ? 29 : 28);
|
||||
}
|
||||
if (month >= 1 && month <= 12) {
|
||||
return kDays[month - 1];
|
||||
}
|
||||
return 30;
|
||||
}
|
||||
|
||||
static bool isValidDateTime(const DateTime& dt) {
|
||||
if (dt.year < 2000U || dt.year > 2099U) return false;
|
||||
if (dt.month < 1 || dt.month > 12) return false;
|
||||
if (dt.day < 1 || dt.day > daysInMonth(dt.year, dt.month)) return false;
|
||||
if (dt.hour > 23 || dt.minute > 59 || dt.second > 59) return false;
|
||||
return true;
|
||||
}
|
||||
|
||||
static int64_t daysFromCivil(int y, unsigned m, unsigned d) {
|
||||
y -= (m <= 2);
|
||||
const int era = (y >= 0 ? y : y - 399) / 400;
|
||||
const unsigned yoe = (unsigned)(y - era * 400);
|
||||
const unsigned doy = (153 * (m + (m > 2 ? (unsigned)-3 : 9)) + 2) / 5 + d - 1;
|
||||
const unsigned doe = yoe * 365 + yoe / 4 - yoe / 100 + doy;
|
||||
return era * 146097 + (int)doe - 719468;
|
||||
}
|
||||
|
||||
static int64_t toEpochSeconds(const DateTime& dt) {
|
||||
int64_t days = daysFromCivil((int)dt.year, dt.month, dt.day);
|
||||
return days * 86400LL + (int64_t)dt.hour * 3600LL + (int64_t)dt.minute * 60LL + (int64_t)dt.second;
|
||||
}
|
||||
|
||||
static bool fromEpochSeconds(int64_t sec, DateTime& out) {
|
||||
if (sec < 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
int64_t days = sec / 86400LL;
|
||||
int64_t rem = sec % 86400LL;
|
||||
if (rem < 0) {
|
||||
rem += 86400LL;
|
||||
days -= 1;
|
||||
}
|
||||
|
||||
out.hour = (uint8_t)(rem / 3600LL);
|
||||
rem %= 3600LL;
|
||||
out.minute = (uint8_t)(rem / 60LL);
|
||||
out.second = (uint8_t)(rem % 60LL);
|
||||
|
||||
days += 719468;
|
||||
const int era = (days >= 0 ? days : days - 146096) / 146097;
|
||||
const unsigned doe = (unsigned)(days - era * 146097);
|
||||
const unsigned yoe = (doe - doe / 1460 + doe / 36524 - doe / 146096) / 365;
|
||||
int y = (int)yoe + era * 400;
|
||||
const unsigned doy = doe - (365 * yoe + yoe / 4 - yoe / 100);
|
||||
const unsigned mp = (5 * doy + 2) / 153;
|
||||
const unsigned d = doy - (153 * mp + 2) / 5 + 1;
|
||||
const unsigned m = mp + (mp < 10 ? 3 : (unsigned)-9);
|
||||
y += (m <= 2);
|
||||
|
||||
out.year = (uint16_t)y;
|
||||
out.month = (uint8_t)m;
|
||||
out.day = (uint8_t)d;
|
||||
return isValidDateTime(out);
|
||||
}
|
||||
|
||||
static void addOneSecond(DateTime& dt) {
|
||||
int64_t t = toEpochSeconds(dt);
|
||||
DateTime out{};
|
||||
if (fromEpochSeconds(t + 1, out)) {
|
||||
dt = out;
|
||||
}
|
||||
}
|
||||
|
||||
static void formatUtcCompact(const DateTime& dt, char* out, size_t outLen) {
|
||||
snprintf(out,
|
||||
outLen,
|
||||
"%04u%02u%02u_%02u%02u%02u_z",
|
||||
(unsigned)dt.year,
|
||||
(unsigned)dt.month,
|
||||
(unsigned)dt.day,
|
||||
(unsigned)dt.hour,
|
||||
(unsigned)dt.minute,
|
||||
(unsigned)dt.second);
|
||||
}
|
||||
|
||||
static void formatUtcHuman(const DateTime& dt, char* out, size_t outLen) {
|
||||
snprintf(out,
|
||||
outLen,
|
||||
"%04u-%02u-%02u %02u:%02u:%02u UTC",
|
||||
(unsigned)dt.year,
|
||||
(unsigned)dt.month,
|
||||
(unsigned)dt.day,
|
||||
(unsigned)dt.hour,
|
||||
(unsigned)dt.minute,
|
||||
(unsigned)dt.second);
|
||||
}
|
||||
|
||||
static bool parseUInt2(const char* s, uint8_t& out) {
|
||||
if (!s || !isdigit((unsigned char)s[0]) || !isdigit((unsigned char)s[1])) {
|
||||
return false;
|
||||
}
|
||||
out = (uint8_t)((s[0] - '0') * 10 + (s[1] - '0'));
|
||||
return true;
|
||||
}
|
||||
|
||||
static void parseGga(char* fields[], int count) {
|
||||
if (count <= 7) {
|
||||
return;
|
||||
}
|
||||
int sats = atoi(fields[7]);
|
||||
if (sats >= 0 && sats <= 255) {
|
||||
g_gps.satsUsed = (uint8_t)sats;
|
||||
}
|
||||
}
|
||||
|
||||
static void parseGsv(char* fields[], int count) {
|
||||
if (count <= 3) {
|
||||
return;
|
||||
}
|
||||
int sats = atoi(fields[3]);
|
||||
if (sats >= 0 && sats <= 255) {
|
||||
g_gps.satsInView = (uint8_t)sats;
|
||||
}
|
||||
}
|
||||
|
||||
static void parseRmc(char* fields[], int count) {
|
||||
if (count <= 9) {
|
||||
return;
|
||||
}
|
||||
|
||||
const char* utc = fields[1];
|
||||
const char* status = fields[2];
|
||||
const char* date = fields[9];
|
||||
|
||||
if (!status || status[0] != 'A') {
|
||||
return;
|
||||
}
|
||||
|
||||
if (!utc || strlen(utc) < 6 || !date || strlen(date) < 6) {
|
||||
return;
|
||||
}
|
||||
|
||||
uint8_t hh = 0, mm = 0, ss = 0;
|
||||
uint8_t dd = 0, mo = 0, yy = 0;
|
||||
if (!parseUInt2(utc + 0, hh) || !parseUInt2(utc + 2, mm) || !parseUInt2(utc + 4, ss)) {
|
||||
return;
|
||||
}
|
||||
if (!parseUInt2(date + 0, dd) || !parseUInt2(date + 2, mo) || !parseUInt2(date + 4, yy)) {
|
||||
return;
|
||||
}
|
||||
|
||||
g_gps.utc.hour = hh;
|
||||
g_gps.utc.minute = mm;
|
||||
g_gps.utc.second = ss;
|
||||
g_gps.utc.day = dd;
|
||||
g_gps.utc.month = mo;
|
||||
g_gps.utc.year = (uint16_t)(2000U + yy);
|
||||
g_gps.hasValidUtc = true;
|
||||
g_gps.lastUtcMs = millis();
|
||||
}
|
||||
|
||||
static void processNmeaLine(char* line) {
|
||||
if (!line || line[0] != '$') {
|
||||
return;
|
||||
}
|
||||
|
||||
g_gps.sawAnySentence = true;
|
||||
|
||||
char* star = strchr(line, '*');
|
||||
if (star) {
|
||||
*star = '\0';
|
||||
}
|
||||
|
||||
char* fields[24] = {0};
|
||||
int count = 0;
|
||||
char* saveptr = nullptr;
|
||||
char* tok = strtok_r(line, ",", &saveptr);
|
||||
while (tok && count < 24) {
|
||||
fields[count++] = tok;
|
||||
tok = strtok_r(nullptr, ",", &saveptr);
|
||||
}
|
||||
|
||||
if (count <= 0 || !fields[0]) {
|
||||
return;
|
||||
}
|
||||
|
||||
const char* header = fields[0];
|
||||
size_t n = strlen(header);
|
||||
if (n < 6) {
|
||||
return;
|
||||
}
|
||||
|
||||
const char* type = header + (n - 3);
|
||||
if (strcmp(type, "GGA") == 0) {
|
||||
parseGga(fields, count);
|
||||
} else if (strcmp(type, "GSV") == 0) {
|
||||
parseGsv(fields, count);
|
||||
} else if (strcmp(type, "RMC") == 0) {
|
||||
parseRmc(fields, count);
|
||||
}
|
||||
}
|
||||
|
||||
static void pollGpsSerial() {
|
||||
while (g_gpsSerial.available() > 0) {
|
||||
char c = (char)g_gpsSerial.read();
|
||||
if (c == '\r') {
|
||||
continue;
|
||||
}
|
||||
if (c == '\n') {
|
||||
if (g_gpsLineLen > 0) {
|
||||
g_gpsLine[g_gpsLineLen] = '\0';
|
||||
processNmeaLine(g_gpsLine);
|
||||
g_gpsLineLen = 0;
|
||||
}
|
||||
continue;
|
||||
}
|
||||
|
||||
if (g_gpsLineLen + 1 < sizeof(g_gpsLine)) {
|
||||
g_gpsLine[g_gpsLineLen++] = c;
|
||||
} else {
|
||||
g_gpsLineLen = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static bool collectGpsTraffic(uint32_t windowMs) {
|
||||
uint32_t start = millis();
|
||||
bool sawBytes = false;
|
||||
while ((uint32_t)(millis() - start) < windowMs) {
|
||||
if (g_gpsSerial.available() > 0) {
|
||||
sawBytes = true;
|
||||
}
|
||||
pollGpsSerial();
|
||||
g_sd.update();
|
||||
delay(2);
|
||||
}
|
||||
return sawBytes || g_gps.sawAnySentence;
|
||||
}
|
||||
|
||||
static void initialGpsProbe() {
|
||||
logf("GPS startup probe at %u baud", (unsigned)GPS_BAUD);
|
||||
(void)collectGpsTraffic(kGpsStartupProbeMs);
|
||||
logf("GPS probe complete: nmea=%s sats_used=%u sats_view=%u utc=%s",
|
||||
g_gps.sawAnySentence ? "yes" : "no",
|
||||
(unsigned)g_gps.satsUsed,
|
||||
(unsigned)g_gps.satsInView,
|
||||
g_gps.hasValidUtc ? "yes" : "no");
|
||||
}
|
||||
|
||||
static IRAM_ATTR void onPpsEdge() {
|
||||
g_ppsEdgeCount++;
|
||||
}
|
||||
|
||||
static uint8_t bestSatelliteCount() {
|
||||
return (g_gps.satsUsed > g_gps.satsInView) ? g_gps.satsUsed : g_gps.satsInView;
|
||||
}
|
||||
|
||||
static bool ensureGpsLogPathReady() {
|
||||
if (!g_sd.isMounted()) {
|
||||
g_gpsPathReady = false;
|
||||
return false;
|
||||
}
|
||||
|
||||
if (g_gpsPathReady) {
|
||||
return true;
|
||||
}
|
||||
|
||||
if (!g_sd.ensureDirRecursive("/gps")) {
|
||||
logf("Could not create /gps directory");
|
||||
return false;
|
||||
}
|
||||
|
||||
// Touch the log file so a clean SD card is prepared before first discipline event.
|
||||
File f = SD.open("/gps/discipline_rtc.log", FILE_APPEND);
|
||||
if (!f) {
|
||||
logf("Could not open /gps/discipline_rtc.log for append");
|
||||
return false;
|
||||
}
|
||||
f.close();
|
||||
|
||||
g_gpsPathReady = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool appendDisciplineLog(const DateTime& gpsUtc, int64_t rtcMinusGpsSeconds) {
|
||||
if (!ensureGpsLogPathReady()) {
|
||||
logf("SD not mounted, skipping append to gps/discipline_rtc.log");
|
||||
return false;
|
||||
}
|
||||
|
||||
File f = SD.open("/gps/discipline_rtc.log", FILE_APPEND);
|
||||
if (!f) {
|
||||
logf("Could not open /gps/discipline_rtc.log for append");
|
||||
return false;
|
||||
}
|
||||
|
||||
char ts[32];
|
||||
formatUtcCompact(gpsUtc, ts, sizeof(ts));
|
||||
|
||||
char line[220];
|
||||
snprintf(line,
|
||||
sizeof(line),
|
||||
"%s\t set RTC to GPS using 1PPS pulse-per-second discipline\trtc-gps drift=%+lld s",
|
||||
ts,
|
||||
(long long)rtcMinusGpsSeconds);
|
||||
|
||||
size_t wrote = f.println(line);
|
||||
f.close();
|
||||
if (wrote == 0) {
|
||||
logf("Append write failed: /gps/discipline_rtc.log");
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool gpsUtcIsFresh() {
|
||||
if (!g_gps.hasValidUtc) {
|
||||
return false;
|
||||
}
|
||||
return (uint32_t)(millis() - g_gps.lastUtcMs) <= 2000;
|
||||
}
|
||||
|
||||
static bool waitForNextPps(uint32_t timeoutMs) {
|
||||
uint32_t startCount = g_ppsEdgeCount;
|
||||
uint32_t startMs = millis();
|
||||
while ((uint32_t)(millis() - startMs) < timeoutMs) {
|
||||
pollGpsSerial();
|
||||
g_sd.update();
|
||||
if (g_ppsEdgeCount != startCount) {
|
||||
return true;
|
||||
}
|
||||
delay(2);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
static void waitWithUpdates(uint32_t delayMs) {
|
||||
uint32_t start = millis();
|
||||
while ((uint32_t)(millis() - start) < delayMs) {
|
||||
pollGpsSerial();
|
||||
g_sd.update();
|
||||
delay(10);
|
||||
}
|
||||
}
|
||||
|
||||
static void showNoTimeAndDelay() {
|
||||
uint8_t sats = bestSatelliteCount();
|
||||
char l3[24];
|
||||
snprintf(l3, sizeof(l3), "Satellites: %u", (unsigned)sats);
|
||||
oledShowLines("GPS time unavailable", "RTC NOT disciplined", l3, "Retry in 30 seconds");
|
||||
logf("GPS UTC unavailable. satellites=%u. Waiting 30 seconds.", (unsigned)sats);
|
||||
waitWithUpdates(kNoTimeDelayMs);
|
||||
}
|
||||
|
||||
static bool disciplineRtcToGps() {
|
||||
if (!gpsUtcIsFresh()) {
|
||||
showNoTimeAndDelay();
|
||||
return false;
|
||||
}
|
||||
|
||||
DateTime priorRtc{};
|
||||
bool lowV = false;
|
||||
bool havePriorRtc = rtcRead(priorRtc, lowV);
|
||||
if (havePriorRtc && (lowV || !isValidDateTime(priorRtc))) {
|
||||
havePriorRtc = false;
|
||||
}
|
||||
|
||||
DateTime gpsSnap = g_gps.utc;
|
||||
if (!waitForNextPps(kPpsWaitTimeoutMs)) {
|
||||
oledShowLines("GPS 1PPS missing", "RTC NOT disciplined", "Retry in 30 seconds");
|
||||
logf("No 1PPS edge observed within timeout. Waiting 30 seconds.");
|
||||
waitWithUpdates(kNoTimeDelayMs);
|
||||
return false;
|
||||
}
|
||||
|
||||
DateTime target = gpsSnap;
|
||||
addOneSecond(target);
|
||||
|
||||
if (!rtcWrite(target)) {
|
||||
oledShowLines("RTC write failed", "Could not set from GPS");
|
||||
logf("RTC write failed");
|
||||
return false;
|
||||
}
|
||||
|
||||
int64_t driftSec = 0;
|
||||
if (havePriorRtc) {
|
||||
driftSec = toEpochSeconds(priorRtc) - toEpochSeconds(target);
|
||||
}
|
||||
|
||||
(void)appendDisciplineLog(target, driftSec);
|
||||
|
||||
char utcLine[36];
|
||||
char driftLine[36];
|
||||
formatUtcHuman(target, utcLine, sizeof(utcLine));
|
||||
if (havePriorRtc) {
|
||||
snprintf(driftLine, sizeof(driftLine), "rtc-gps drift: %+lld s", (long long)driftSec);
|
||||
} else {
|
||||
snprintf(driftLine, sizeof(driftLine), "rtc-gps drift: RTC_unset");
|
||||
}
|
||||
|
||||
oledShowLines("RTC disciplined to GPS", utcLine, "Method: 1PPS", driftLine);
|
||||
|
||||
logf("RTC disciplined to GPS with 1PPS. %s drift=%+llds lowV=%s",
|
||||
utcLine,
|
||||
(long long)driftSec,
|
||||
lowV ? "yes" : "no");
|
||||
return true;
|
||||
}
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
delay(kSerialDelayMs);
|
||||
|
||||
Serial.println("\r\n==================================================");
|
||||
Serial.println("Exercise 11: Set RTC to GPS with 1PPS discipline");
|
||||
Serial.println("==================================================");
|
||||
|
||||
if (!tbeam_supreme::initPmuForPeripherals(g_pmu, &Serial)) {
|
||||
logf("PMU init failed");
|
||||
}
|
||||
|
||||
Wire.begin(OLED_SDA, OLED_SCL);
|
||||
g_oled.setI2CAddress(OLED_ADDR << 1);
|
||||
g_oled.begin();
|
||||
oledShowLines("Exercise 11", "RTC <- GPS (1PPS)", "Booting...");
|
||||
|
||||
SdWatcherConfig sdCfg{};
|
||||
if (!g_sd.begin(sdCfg, nullptr)) {
|
||||
logf("SD startup manager begin() failed");
|
||||
}
|
||||
(void)ensureGpsLogPathReady();
|
||||
|
||||
#ifdef GPS_WAKEUP_PIN
|
||||
pinMode(GPS_WAKEUP_PIN, INPUT);
|
||||
#endif
|
||||
#ifdef GPS_1PPS_PIN
|
||||
pinMode(GPS_1PPS_PIN, INPUT);
|
||||
attachInterrupt(digitalPinToInterrupt(GPS_1PPS_PIN), onPpsEdge, RISING);
|
||||
#endif
|
||||
|
||||
g_gpsSerial.setRxBufferSize(1024);
|
||||
g_gpsSerial.begin(GPS_BAUD, SERIAL_8N1, GPS_RX_PIN, GPS_TX_PIN);
|
||||
logf("GPS UART started: RX=%d TX=%d baud=%u", GPS_RX_PIN, GPS_TX_PIN, (unsigned)GPS_BAUD);
|
||||
|
||||
oledShowLines("GPS startup probe", "Checking UTC + 1PPS");
|
||||
initialGpsProbe();
|
||||
|
||||
g_nextDisciplineMs = millis();
|
||||
}
|
||||
|
||||
void loop() {
|
||||
pollGpsSerial();
|
||||
g_sd.update();
|
||||
|
||||
if (g_sd.consumeMountedEvent()) {
|
||||
g_gpsPathReady = false;
|
||||
(void)ensureGpsLogPathReady();
|
||||
}
|
||||
if (g_sd.consumeRemovedEvent()) {
|
||||
g_gpsPathReady = false;
|
||||
}
|
||||
|
||||
uint32_t now = millis();
|
||||
if ((int32_t)(now - g_nextDisciplineMs) >= 0) {
|
||||
bool ok = disciplineRtcToGps();
|
||||
g_nextDisciplineMs = now + (ok ? kLoopMsDiscipline : kNoTimeDelayMs);
|
||||
}
|
||||
|
||||
delay(5);
|
||||
}
|
||||
Loading…
Add table
Add a link
Reference in a new issue