Compare commits

...

7 commits

27 changed files with 4087 additions and 3 deletions

View file

@ -0,0 +1,18 @@
The T-Beam ships with two options:
1) L76K
2) MAX-M10S
NMEA (National Marine Electronics Association) format is a standard protocol used for communication between marine electronics devices, including GPS receivers, chart plotters, and other navigation equipment. It's a text-based, ASCII-encoded format that transmits data in "sentences" — short, comma-separated strings that start with a dollar sign ($) and end with a checksum.
Key Characteristics:
Structure: Each sentence begins with $ followed by a talker ID (e.g., GP for GPS), a sentence type (e.g., GGA for Global Positioning System Fix Data), and data fields separated by commas. It ends with an asterisk (*) and a two-character hexadecimal checksum.
Example: $GPGGA,123519,4807.038,N,01131.000,E,1,08,0.9,545.4,M,46.9,M,,*47
This is a GGA sentence providing time, latitude, longitude, fix quality, number of satellites, etc.
Common Sentence Types (relevant to GPS):
GGA: GPS fix data (position, time, satellites).
RMC: Recommended minimum navigation information (position, speed, course).
GSV: Satellites in view.
TXT: Text messages (e.g., module identification).
Baud Rate: Typically transmitted at 4800 or 9600 baud over serial interfaces.
Usage: Widely used in GPS modules like the L76K and UBLOX MAX-M10S, as seen in your project's code where NMEA sentences are parsed to extract location, time, and satellite data.
In your T-Beam exercises, the code reads serial data from the GPS module, buffers it into lines, and parses these NMEA sentences to detect the module type and extract useful information like UTC time and satellite counts. Both L76K and UBLOX modules output NMEA by default, though UBLOX can also support other formats like UBX binary. If you need details on parsing specific sentences or differences between modules, let me know!

View file

@ -132,3 +132,10 @@ You are saying:
> “Use PlatformIO to build this firmware for the specified environment and flash it to the target device.”
## PlatformIO configuration file
platformio.ini is the configuration file. Each unit should have it's own entry so that the code can automaticaly be modified.
INSERT IMAGE
## Uploading Image
pio run -e flo -t upload --upload-port /dev/ttytFLO

View file

@ -833,11 +833,12 @@ static void gpsLogClear() {
file.close();
Serial.printf("Cleared %s\r\n", kGpsLogPath);
}
// Process a command received on the serial console.
static void processSerialCommand(const char* line) {
if (!line || line[0] == '\0') {
return;
}
// Echo the command back to the console for clarity and posterity.
Serial.printf("-->%s\r\n", line);
if (strcasecmp(line, "help") == 0) {
showGpsLogHelp();
@ -1148,6 +1149,9 @@ void setup() {
logf("PMU init failed");
}
// SPI Flash File System ("SPIFFS") is used for logging GPS diagnostics,
// which may be helpful for analyzing GPS behavior in different
//environments and over time.
g_spiffsReady = SPIFFS.begin(true);
if (!g_spiffsReady) {
logf("SPIFFS mount failed");
@ -1164,12 +1168,14 @@ void setup() {
}
}
// Initialize the OLED display and show a boot message with build info.
Wire.begin(OLED_SDA, OLED_SCL);
g_oled.setI2CAddress(OLED_ADDR << 1);
g_oled.begin();
String buildStamp = buildStampShort();
oledShowLines("09_GPS_Time", buildStamp.c_str(), "Booting...");
// The GPS startup probe may take a while,
//especially for a cold start. Log some
SdWatcherConfig sdCfg{};
if (!g_sd.begin(sdCfg, nullptr)) {
logf("SD startup manager begin() failed");

View file

@ -8,4 +8,13 @@ main.cpp needs to be modified to reflect the number of units. It is a zero-base
INSERT SCREENSHOT HERE.
INSERT SCREENSHOT HERE.
To compile and load:
time pio run -e flo -t upload --upload-port /dev/ttytFLO
To monitor (replace with appropriate unit name) for Exercise 12:
pio device monitor -d /usr/local/src/microreticulum/microReticulumTbeam/exercises/12_FiveTalk -e flo --port /dev/ttytFLO

View file

@ -0,0 +1,38 @@
## Exercise 18: GPS Field QA
Survey/reconnaissance firmware for LilyGO T-Beam SUPREME.
This exercise measures GNSS visibility and solution quality, disciplines the RTC from GNSS before creating any capture log, writes CSV captures to SD card, and exposes the SD tree over the field AP for download and erase operations.
Current storage choice:
- `SD`
Current environments:
- `bob_l76k`
- `guy_ublox`
Primary serial commands:
- `status`
- `summary`
- `ls`
- `cat <path>`
- `erase <path>`
- `stop`
- `start`
- `flush`
- `discipline`
- `erase_logs`
Notes:
- Default environment is `cy`.
- No log file is created until GNSS UTC plus PPS has disciplined the RTC.
- The capture file naming format is `YYYYMMDD_HHMMSS_<BOARD>.csv`.
- Samples are aggregated once per second.
- Records are double-buffered in RAM and flushed to SD every 10 seconds.
- Satellite snapshot records are written as additional CSV lines when GSV data is available.
- The web UI exposes SD download links and `/cmd?...` actions such as `erase=/logs/20260406_093912_CY.csv`.
- The implementation uses common NMEA parsing so it can normalize L76K and MAX-M10S output without adding a new GNSS dependency.

View file

@ -0,0 +1,241 @@
#include "ClockDiscipline.h"
#include "Config.h"
namespace field_qa {
ClockDiscipline::ClockDiscipline(TwoWire& wire) : m_wire(wire) {}
uint8_t ClockDiscipline::toBcd(uint8_t value) {
return (uint8_t)(((value / 10U) << 4U) | (value % 10U));
}
uint8_t ClockDiscipline::fromBcd(uint8_t value) {
return (uint8_t)(((value >> 4U) * 10U) + (value & 0x0FU));
}
bool ClockDiscipline::isLeapYear(uint16_t year) {
return ((year % 4U) == 0U && (year % 100U) != 0U) || ((year % 400U) == 0U);
}
uint8_t ClockDiscipline::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 == 2U) {
return (uint8_t)(isLeapYear(year) ? 29U : 28U);
}
if (month >= 1U && month <= 12U) {
return kDays[month - 1U];
}
return 0;
}
bool ClockDiscipline::isValidDateTime(const ClockDateTime& dt) {
if (dt.year < 2000U || dt.year > 2099U) {
return false;
}
if (dt.month < 1U || dt.month > 12U) {
return false;
}
if (dt.day < 1U || dt.day > daysInMonth(dt.year, dt.month)) {
return false;
}
if (dt.hour > 23U || dt.minute > 59U || dt.second > 59U) {
return false;
}
return true;
}
int64_t ClockDiscipline::daysFromCivil(int year, unsigned month, unsigned day) {
year -= (month <= 2U);
const int era = (year >= 0 ? year : year - 399) / 400;
const unsigned yoe = (unsigned)(year - era * 400);
const unsigned doy = (153U * (month + (month > 2U ? (unsigned)-3 : 9U)) + 2U) / 5U + day - 1U;
const unsigned doe = yoe * 365U + yoe / 4U - yoe / 100U + doy;
return era * 146097 + (int)doe - 719468;
}
int64_t ClockDiscipline::toEpochSeconds(const ClockDateTime& dt) {
const 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;
}
bool ClockDiscipline::fromEpochSeconds(int64_t seconds, ClockDateTime& out) {
if (seconds < 0) {
return false;
}
int64_t days = seconds / 86400LL;
int64_t remainder = seconds % 86400LL;
if (remainder < 0) {
remainder += 86400LL;
days -= 1;
}
out.hour = (uint8_t)(remainder / 3600LL);
remainder %= 3600LL;
out.minute = (uint8_t)(remainder / 60LL);
out.second = (uint8_t)(remainder % 60LL);
days += 719468;
const int era = (days >= 0 ? days : days - 146096) / 146097;
const unsigned doe = (unsigned)(days - era * 146097);
const unsigned yoe = (doe - doe / 1460U + doe / 36524U - doe / 146096U) / 365U;
int year = (int)yoe + era * 400;
const unsigned doy = doe - (365U * yoe + yoe / 4U - yoe / 100U);
const unsigned mp = (5U * doy + 2U) / 153U;
const unsigned day = doy - (153U * mp + 2U) / 5U + 1U;
const unsigned month = mp + (mp < 10U ? 3U : (unsigned)-9);
year += (month <= 2U);
out.year = (uint16_t)year;
out.month = (uint8_t)month;
out.day = (uint8_t)day;
return isValidDateTime(out);
}
bool ClockDiscipline::readRtc(ClockDateTime& out, bool& lowVoltageFlag) const {
m_wire.beginTransmission(RTC_I2C_ADDR);
m_wire.write(0x02);
if (m_wire.endTransmission(false) != 0) {
return false;
}
const uint8_t need = 7;
const uint8_t got = m_wire.requestFrom((int)RTC_I2C_ADDR, (int)need);
if (got != need) {
return false;
}
const uint8_t sec = m_wire.read();
const uint8_t min = m_wire.read();
const uint8_t hour = m_wire.read();
const uint8_t day = m_wire.read();
(void)m_wire.read();
const uint8_t month = m_wire.read();
const uint8_t year = m_wire.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);
const uint8_t yy = fromBcd(year);
out.year = (month & 0x80U) ? (1900U + yy) : (2000U + yy);
return true;
}
bool ClockDiscipline::readValidRtc(ClockDateTime& out, int64_t* epochOut) const {
bool lowVoltage = false;
if (!readRtc(out, lowVoltage) || lowVoltage || !isValidDateTime(out)) {
return false;
}
if (epochOut != nullptr) {
*epochOut = toEpochSeconds(out);
}
return true;
}
bool ClockDiscipline::writeRtc(const ClockDateTime& dt) const {
if (!isValidDateTime(dt)) {
return false;
}
m_wire.beginTransmission(RTC_I2C_ADDR);
m_wire.write(0x02);
m_wire.write(toBcd(dt.second & 0x7FU));
m_wire.write(toBcd(dt.minute));
m_wire.write(toBcd(dt.hour));
m_wire.write(toBcd(dt.day));
m_wire.write(0x00);
uint8_t monthReg = toBcd(dt.month);
if (dt.year < 2000U) {
monthReg |= 0x80U;
}
m_wire.write(monthReg);
m_wire.write(toBcd((uint8_t)(dt.year % 100U)));
return m_wire.endTransmission() == 0;
}
void ClockDiscipline::formatIsoUtc(const ClockDateTime& dt, char* out, size_t outSize) {
snprintf(out,
outSize,
"%04u-%02u-%02uT%02u:%02u:%02uZ",
(unsigned)dt.year,
(unsigned)dt.month,
(unsigned)dt.day,
(unsigned)dt.hour,
(unsigned)dt.minute,
(unsigned)dt.second);
}
void ClockDiscipline::formatCompactUtc(const ClockDateTime& dt, char* out, size_t outSize) {
snprintf(out,
outSize,
"%04u%02u%02u_%02u%02u%02u",
(unsigned)dt.year,
(unsigned)dt.month,
(unsigned)dt.day,
(unsigned)dt.hour,
(unsigned)dt.minute,
(unsigned)dt.second);
}
void ClockDiscipline::makeRunId(const ClockDateTime& dt, const char* boardId, char* out, size_t outSize) {
snprintf(out,
outSize,
"%04u%02u%02u_%02u%02u%02u_%s",
(unsigned)dt.year,
(unsigned)dt.month,
(unsigned)dt.day,
(unsigned)dt.hour,
(unsigned)dt.minute,
(unsigned)dt.second,
boardId ? boardId : "NODE");
}
bool ClockDiscipline::fromGnssSample(const GnssSample& sample, ClockDateTime& out) {
if (!sample.validTime) {
return false;
}
out.year = sample.year;
out.month = sample.month;
out.day = sample.day;
out.hour = sample.hour;
out.minute = sample.minute;
out.second = sample.second;
return isValidDateTime(out);
}
bool ClockDiscipline::disciplineFromGnss(const GnssSample& sample,
WaitForPpsCallback waitForPps,
void* context,
ClockDateTime& disciplinedUtc,
bool& hadPriorRtc,
int64_t& driftSeconds) const {
ClockDateTime gpsUtc{};
if (!fromGnssSample(sample, gpsUtc) || waitForPps == nullptr) {
return false;
}
ClockDateTime priorRtc{};
hadPriorRtc = readValidRtc(priorRtc, nullptr);
if (!waitForPps(context, kClockPpsWaitTimeoutMs)) {
return false;
}
const int64_t snappedEpoch = toEpochSeconds(gpsUtc);
if (!fromEpochSeconds(snappedEpoch + 1, disciplinedUtc)) {
return false;
}
if (!writeRtc(disciplinedUtc)) {
return false;
}
driftSeconds = hadPriorRtc ? (toEpochSeconds(priorRtc) - toEpochSeconds(disciplinedUtc)) : 0;
return true;
}
} // namespace field_qa

View file

@ -0,0 +1,53 @@
#pragma once
#include <Arduino.h>
#include <Wire.h>
#include "GnssTypes.h"
namespace field_qa {
struct ClockDateTime {
uint16_t year = 0;
uint8_t month = 0;
uint8_t day = 0;
uint8_t hour = 0;
uint8_t minute = 0;
uint8_t second = 0;
};
using WaitForPpsCallback = bool (*)(void* context, uint32_t timeoutMs);
class ClockDiscipline {
public:
explicit ClockDiscipline(TwoWire& wire = Wire1);
bool readRtc(ClockDateTime& out, bool& lowVoltageFlag) const;
bool readValidRtc(ClockDateTime& out, int64_t* epochOut = nullptr) const;
bool writeRtc(const ClockDateTime& dt) const;
bool disciplineFromGnss(const GnssSample& sample,
WaitForPpsCallback waitForPps,
void* context,
ClockDateTime& disciplinedUtc,
bool& hadPriorRtc,
int64_t& driftSeconds) const;
static bool isValidDateTime(const ClockDateTime& dt);
static int64_t toEpochSeconds(const ClockDateTime& dt);
static bool fromEpochSeconds(int64_t seconds, ClockDateTime& out);
static void formatIsoUtc(const ClockDateTime& dt, char* out, size_t outSize);
static void formatCompactUtc(const ClockDateTime& dt, char* out, size_t outSize);
static void makeRunId(const ClockDateTime& dt, const char* boardId, char* out, size_t outSize);
static bool fromGnssSample(const GnssSample& sample, ClockDateTime& out);
private:
static uint8_t toBcd(uint8_t value);
static uint8_t fromBcd(uint8_t value);
static bool isLeapYear(uint16_t year);
static uint8_t daysInMonth(uint16_t year, uint8_t month);
static int64_t daysFromCivil(int year, unsigned month, unsigned day);
TwoWire& m_wire;
};
} // namespace field_qa

View file

@ -0,0 +1,84 @@
#pragma once
#include <Arduino.h>
#ifndef BOARD_ID
#define BOARD_ID "BOB"
#endif
#ifndef GNSS_CHIP_NAME
#define GNSS_CHIP_NAME "L76K"
#endif
#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 GPS_RX_PIN
#define GPS_RX_PIN 9
#endif
#ifndef GPS_TX_PIN
#define GPS_TX_PIN 8
#endif
#ifndef BUTTON_PIN
#define BUTTON_PIN 0
#endif
#ifndef FW_BUILD_UTC
#define FW_BUILD_UTC unknown
#endif
#define FIELD_QA_STR_INNER(x) #x
#define FIELD_QA_STR(x) FIELD_QA_STR_INNER(x)
namespace field_qa {
static constexpr const char* kExerciseName = "18_GPS_Field_QA";
static constexpr const char* kFirmwareVersion = FIELD_QA_STR(FW_BUILD_UTC);
static constexpr const char* kBoardId = BOARD_ID;
static constexpr const char* kGnssChip = GNSS_CHIP_NAME;
static constexpr const char* kStorageName = "SD";
static constexpr const char* kLogDir = "/logs";
static constexpr const char* kLogApPrefix = "GPSQA-";
static constexpr const char* kLogApPassword = "";
static constexpr uint8_t kLogApIpOctet = 23;
static constexpr uint32_t kSerialDelayMs = 4000;
static constexpr uint32_t kSamplePeriodMs = 1000;
static constexpr uint32_t kLogFlushPeriodMs = 10000;
static constexpr uint32_t kDisplayPeriodMs = 1000;
static constexpr uint32_t kStatusPeriodMs = 1000;
static constexpr uint32_t kProbeWindowL76kMs = 20000;
static constexpr uint32_t kProbeWindowUbloxMs = 45000;
static constexpr uint32_t kFixFreshMs = 5000;
static constexpr uint8_t kPoorMinSatsUsed = 4;
static constexpr uint8_t kGoodMinSatsUsed = 10;
static constexpr uint8_t kExcellentMinSatsUsed = 16;
static constexpr float kMarginalHdop = 3.0f;
static constexpr float kExcellentHdop = 1.5f;
static constexpr size_t kBufferedSamples = 10;
static constexpr size_t kMaxSatellites = 64;
static constexpr size_t kStorageBufferBytes = 4096;
static constexpr uint32_t kClockDisciplineRetryMs = 5000;
static constexpr uint32_t kClockPpsWaitTimeoutMs = 1500;
static constexpr uint32_t kClockFreshSampleMs = 2000;
static constexpr uint32_t kMaxLogFilesBeforePause = 1000;
} // namespace field_qa

View file

@ -0,0 +1,72 @@
#include "DisplayManager.h"
#include <Wire.h>
#include "Config.h"
namespace field_qa {
namespace {
static void formatElapsed(uint32_t ms, char* out, size_t outSize) {
const uint32_t sec = ms / 1000U;
const uint32_t hh = sec / 3600U;
const uint32_t mm = (sec % 3600U) / 60U;
const uint32_t ss = sec % 60U;
snprintf(out, outSize, "%02lu:%02lu:%02lu", (unsigned long)hh, (unsigned long)mm, (unsigned long)ss);
}
} // namespace
void DisplayManager::begin() {
Wire.begin(OLED_SDA, OLED_SCL);
m_oled.setI2CAddress(OLED_ADDR << 1);
m_oled.begin();
}
void DisplayManager::drawLines(const char* l1,
const char* l2,
const char* l3,
const char* l4,
const char* l5,
const char* l6) {
m_oled.clearBuffer();
m_oled.setFont(u8g2_font_5x8_tf);
if (l1) m_oled.drawUTF8(0, 10, l1);
if (l2) m_oled.drawUTF8(0, 20, l2);
if (l3) m_oled.drawUTF8(0, 30, l3);
if (l4) m_oled.drawUTF8(0, 40, l4);
if (l5) m_oled.drawUTF8(0, 50, l5);
if (l6) m_oled.drawUTF8(0, 60, l6);
m_oled.sendBuffer();
}
void DisplayManager::showBoot(const char* line2, const char* line3) {
drawLines(kExerciseName, kFirmwareVersion, line2, line3);
}
void DisplayManager::showError(const char* line1, const char* line2) {
drawLines(kExerciseName, "ERROR", line1, line2);
}
void DisplayManager::showSample(const GnssSample& sample, const RunStats& stats, bool recording) {
char l1[24];
char l2[20];
char l3[20];
char l4[20];
char l5[20];
char l6[20];
snprintf(l1, sizeof(l1), "%s", recording ? "*RECORDING" : "Halted");
snprintf(l2, sizeof(l2), "FIX: %s", fixTypeToString(sample.fixType));
snprintf(l3, sizeof(l3), "USED: %d/%d", sample.satsUsed < 0 ? 0 : sample.satsUsed, sample.satsInView < 0 ? 0 : sample.satsInView);
if (sample.validHdop) {
snprintf(l4, sizeof(l4), "HDOP: %.1f", sample.hdop);
} else {
snprintf(l4, sizeof(l4), "HDOP: --");
}
snprintf(l5, sizeof(l5), "Q: %s", qualityClassForSample(sample));
formatElapsed(stats.elapsedMs(millis()), l6, sizeof(l6));
drawLines(l1, l2, l3, l4, l5, l6);
}
} // namespace field_qa

View file

@ -0,0 +1,28 @@
#pragma once
#include <Arduino.h>
#include <U8g2lib.h>
#include "GnssTypes.h"
#include "RunStats.h"
namespace field_qa {
class DisplayManager {
public:
void begin();
void showBoot(const char* line2, const char* line3 = nullptr);
void showError(const char* line1, const char* line2 = nullptr);
void showSample(const GnssSample& sample, const RunStats& stats, bool recording);
private:
void drawLines(const char* l1,
const char* l2 = nullptr,
const char* l3 = nullptr,
const char* l4 = nullptr,
const char* l5 = nullptr,
const char* l6 = nullptr);
U8G2_SH1106_128X64_NONAME_F_HW_I2C m_oled{U8G2_R0, U8X8_PIN_NONE};
};
} // namespace field_qa

View file

@ -0,0 +1,488 @@
#include "GnssManager.h"
#include <ctype.h>
#include <math.h>
#include <string.h>
#include "Config.h"
namespace field_qa {
namespace {
enum class GpsModuleKind : uint8_t {
Unknown = 0,
L76K,
Ublox
};
#if defined(GPS_UBLOX)
static constexpr GpsModuleKind kExpectedGpsModule = GpsModuleKind::Ublox;
#elif defined(GPS_L76K)
static constexpr GpsModuleKind kExpectedGpsModule = GpsModuleKind::L76K;
#else
static constexpr GpsModuleKind kExpectedGpsModule = GpsModuleKind::Unknown;
#endif
static GpsModuleKind talkerToConstellation(const char* talker) {
if (!talker) return GpsModuleKind::Unknown;
if (strcmp(talker, "GP") == 0) return GpsModuleKind::L76K;
if (strcmp(talker, "GA") == 0) return GpsModuleKind::Ublox;
return GpsModuleKind::Unknown;
}
static FixType fixTypeFromQuality(int quality, int dimension) {
switch (quality) {
case 2:
return FixType::Dgps;
case 4:
return FixType::RtkFixed;
case 5:
return FixType::RtkFloat;
default:
if (dimension >= 3) return FixType::Fix3D;
if (dimension == 2) return FixType::Fix2D;
return FixType::NoFix;
}
}
static void copyTalker(const char* header, char* out) {
if (!header || strlen(header) < 3) {
out[0] = '?';
out[1] = '?';
out[2] = '\0';
return;
}
out[0] = header[1];
out[1] = header[2];
out[2] = '\0';
}
} // namespace
void GnssManager::begin() {
m_bootMs = millis();
strlcpy(m_detectedChip, kGnssChip, sizeof(m_detectedChip));
#ifdef GPS_1PPS_PIN
pinMode(GPS_1PPS_PIN, INPUT);
#endif
#ifdef GPS_WAKEUP_PIN
pinMode(GPS_WAKEUP_PIN, INPUT);
#endif
startUart(GPS_BAUD, GPS_RX_PIN, GPS_TX_PIN);
}
void GnssManager::startUart(uint32_t baud, int rxPin, int txPin) {
m_serial.end();
delay(20);
m_serial.setRxBufferSize(2048);
m_serial.begin(baud, SERIAL_8N1, rxPin, txPin);
}
bool GnssManager::collectTraffic(uint32_t windowMs) {
uint32_t start = millis();
bool sawBytes = false;
while ((uint32_t)(millis() - start) < windowMs) {
if (m_serial.available() > 0) {
sawBytes = true;
}
poll();
delay(2);
}
return sawBytes || m_sawSentence;
}
bool GnssManager::probeAtBaud(uint32_t baud, int rxPin, int txPin) {
startUart(baud, rxPin, txPin);
if (collectTraffic(700)) {
return true;
}
m_serial.write("$PCAS06,0*1B\r\n");
m_serial.write("$PMTK605*31\r\n");
m_serial.write("$PQTMVERNO*58\r\n");
m_serial.write("$PUBX,00*33\r\n");
m_serial.write("$PMTK353,1,1,1,1,1*2A\r\n");
m_serial.write("$PMTK314,0,1,0,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0*29\r\n");
return collectTraffic(1200);
}
bool GnssManager::probeAtStartup(Stream& serialOut) {
const uint32_t bauds[] = {GPS_BAUD, 115200, 38400, 57600, 19200};
int pins[2][2] = {{GPS_RX_PIN, GPS_TX_PIN}, {34, 12}};
size_t pinCount = (kExpectedGpsModule == GpsModuleKind::Ublox && !(GPS_RX_PIN == 34 && GPS_TX_PIN == 12)) ? 2 : 1;
for (size_t p = 0; p < pinCount; ++p) {
for (size_t i = 0; i < sizeof(bauds) / sizeof(bauds[0]); ++i) {
if (probeAtBaud(bauds[i], pins[p][0], pins[p][1])) {
serialOut.printf("GPS traffic detected at baud=%lu rx=%d tx=%d\n",
(unsigned long)bauds[i], pins[p][0], pins[p][1]);
return true;
}
}
}
serialOut.println("WARNING: no GPS traffic detected during startup probe");
return false;
}
bool GnssManager::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;
}
double GnssManager::parseNmeaCoord(const char* value, const char* hemi) {
if (!value || !value[0] || !hemi || !hemi[0]) {
return 0.0;
}
double raw = atof(value);
double deg = floor(raw / 100.0);
double minutes = raw - (deg * 100.0);
double result = deg + minutes / 60.0;
if (hemi[0] == 'S' || hemi[0] == 'W') {
result = -result;
}
return result;
}
int GnssManager::splitCsvPreserveEmpty(char* line, char* fields[], int maxFields) {
if (!line || !fields || maxFields <= 0) {
return 0;
}
int count = 0;
char* p = line;
fields[count++] = p;
while (*p && count < maxFields) {
if (*p == ',') {
*p = '\0';
fields[count++] = p + 1;
}
++p;
}
return count;
}
void GnssManager::parseGga(char* fields[], int count) {
if (count < 10) {
return;
}
const int quality = atoi(fields[6]);
const int satsUsed = atoi(fields[7]);
if (satsUsed >= 0) {
m_state.satsUsed = satsUsed;
}
if (fields[8] && fields[8][0]) {
m_state.hdop = atof(fields[8]);
m_state.validHdop = true;
}
if (fields[9] && fields[9][0]) {
m_state.altitudeM = atof(fields[9]);
m_state.validAltitude = true;
}
if (fields[2] && fields[2][0] && fields[4] && fields[4][0]) {
m_state.latitude = parseNmeaCoord(fields[2], fields[3]);
m_state.longitude = parseNmeaCoord(fields[4], fields[5]);
m_state.validLocation = true;
}
if (quality > 0) {
m_state.validFix = true;
m_lastFixMs = millis();
} else {
m_state.validFix = false;
}
m_state.fixType = fixTypeFromQuality(quality, m_state.fixDimension);
}
void GnssManager::parseGsa(char* fields[], int count) {
if (count < 18) {
return;
}
const int dim = atoi(fields[2]);
m_state.fixDimension = dim;
if (count > 15 && fields[15] && fields[15][0]) {
m_state.pdop = atof(fields[15]);
m_state.validPdop = true;
}
if (count > 16 && fields[16] && fields[16][0]) {
m_state.hdop = atof(fields[16]);
m_state.validHdop = true;
}
if (count > 17 && fields[17] && fields[17][0]) {
m_state.vdop = atof(fields[17]);
m_state.validVdop = true;
}
int satsUsed = 0;
m_usedPrnCount = 0;
for (int i = 3; i <= 14 && i < count; ++i) {
if (fields[i] && fields[i][0]) {
++satsUsed;
if (m_usedPrnCount < sizeof(m_usedPrns) / sizeof(m_usedPrns[0])) {
m_usedPrns[m_usedPrnCount++] = (uint8_t)atoi(fields[i]);
}
}
}
if (satsUsed > 0) {
m_state.satsUsed = satsUsed;
}
if (dim >= 2) {
m_state.validFix = true;
m_lastFixMs = millis();
}
m_state.fixType = fixTypeFromQuality(m_state.validFix ? 1 : 0, dim);
}
void GnssManager::clearSatelliteView() {
m_satCount = 0;
for (size_t i = 0; i < kMaxSatellites; ++i) {
m_satellites[i] = SatelliteInfo{};
}
m_state.gpsCount = 0;
m_state.galileoCount = 0;
m_state.glonassCount = 0;
m_state.beidouCount = 0;
m_state.navicCount = 0;
m_state.qzssCount = 0;
m_state.sbasCount = 0;
m_state.meanSnr = -1.0f;
m_state.maxSnr = 0;
}
void GnssManager::finalizeSatelliteStats() {
uint32_t snrSum = 0;
uint32_t snrCount = 0;
for (size_t i = 0; i < m_satCount; ++i) {
SatelliteInfo& sat = m_satellites[i];
if (!sat.valid) {
continue;
}
sat.usedInSolution = prnUsedInSolution(sat.prn);
if (strcmp(sat.talker, "GP") == 0 || strcmp(sat.talker, "GN") == 0) {
++m_state.gpsCount;
} else if (strcmp(sat.talker, "GA") == 0) {
++m_state.galileoCount;
} else if (strcmp(sat.talker, "GL") == 0) {
++m_state.glonassCount;
} else if (strcmp(sat.talker, "GB") == 0 || strcmp(sat.talker, "BD") == 0) {
++m_state.beidouCount;
} else if (strcmp(sat.talker, "GI") == 0) {
++m_state.navicCount;
} else if (strcmp(sat.talker, "GQ") == 0) {
++m_state.qzssCount;
} else if (strcmp(sat.talker, "GS") == 0) {
++m_state.sbasCount;
}
if (sat.snr > 0) {
snrSum += sat.snr;
++snrCount;
if (sat.snr > m_state.maxSnr) {
m_state.maxSnr = sat.snr;
}
}
}
m_state.meanSnr = snrCount > 0 ? ((float)snrSum / (float)snrCount) : -1.0f;
}
void GnssManager::parseGsv(char* fields[], int count) {
if (count < 4) {
return;
}
const int totalMsgs = atoi(fields[1]);
const int msgNum = atoi(fields[2]);
const int satsInView = atoi(fields[3]);
if (msgNum == 1) {
clearSatelliteView();
}
if (satsInView >= 0) {
m_state.satsInView = satsInView;
}
char talker[3];
copyTalker(fields[0], talker);
for (int i = 4; i + 3 < count && m_satCount < kMaxSatellites; i += 4) {
if (!fields[i] || !fields[i][0]) {
continue;
}
SatelliteInfo& sat = m_satellites[m_satCount++];
sat.valid = true;
sat.talker[0] = talker[0];
sat.talker[1] = talker[1];
sat.talker[2] = '\0';
sat.prn = (uint8_t)atoi(fields[i]);
sat.usedInSolution = prnUsedInSolution(sat.prn);
sat.elevation = (uint8_t)atoi(fields[i + 1]);
sat.azimuth = (uint16_t)atoi(fields[i + 2]);
sat.snr = (uint8_t)atoi(fields[i + 3]);
}
if (msgNum == totalMsgs) {
finalizeSatelliteStats();
}
m_lastGsvMs = millis();
}
bool GnssManager::prnUsedInSolution(uint8_t prn) const {
for (size_t i = 0; i < m_usedPrnCount; ++i) {
if (m_usedPrns[i] == prn) {
return true;
}
}
return false;
}
void GnssManager::parseRmc(char* fields[], int count) {
if (count < 10) {
return;
}
const char* utc = fields[1];
const char* status = fields[2];
if (status && status[0] == 'A') {
m_state.validFix = true;
m_lastFixMs = millis();
}
if (utc && strlen(utc) >= 6 && fields[9] && strlen(fields[9]) >= 6) {
uint8_t hh = 0, mm = 0, ss = 0, dd = 0, mo = 0, yy = 0;
if (parseUInt2(utc + 0, hh) && parseUInt2(utc + 2, mm) && parseUInt2(utc + 4, ss) &&
parseUInt2(fields[9] + 0, dd) && parseUInt2(fields[9] + 2, mo) && parseUInt2(fields[9] + 4, yy)) {
m_state.hour = hh;
m_state.minute = mm;
m_state.second = ss;
m_state.day = dd;
m_state.month = mo;
m_state.year = (uint16_t)(2000U + yy);
m_state.validTime = true;
}
}
if (fields[3] && fields[3][0] && fields[5] && fields[5][0]) {
m_state.latitude = parseNmeaCoord(fields[3], fields[4]);
m_state.longitude = parseNmeaCoord(fields[5], fields[6]);
m_state.validLocation = true;
}
if (fields[7] && fields[7][0]) {
m_state.speedMps = (float)(atof(fields[7]) * 0.514444);
m_state.validSpeed = true;
}
if (fields[8] && fields[8][0]) {
m_state.courseDeg = atof(fields[8]);
m_state.validCourse = true;
}
}
void GnssManager::parseVtg(char* fields[], int count) {
if (count > 1 && fields[1] && fields[1][0]) {
m_state.courseDeg = atof(fields[1]);
m_state.validCourse = true;
}
if (count > 7 && fields[7] && fields[7][0]) {
m_state.speedMps = (float)(atof(fields[7]) / 3.6);
m_state.validSpeed = true;
}
}
void GnssManager::parseTxt(char* fields[], int count) {
if (count <= 4 || !fields[4]) {
return;
}
String text(fields[4]);
text.toUpperCase();
if (text.indexOf("L76K") >= 0 || text.indexOf("QUECTEL") >= 0) {
strlcpy(m_detectedChip, "L76K", sizeof(m_detectedChip));
}
}
void GnssManager::processNmeaLine(char* line) {
if (!line || line[0] != '$') {
return;
}
m_sawSentence = true;
m_state.sawSentence = true;
char* star = strchr(line, '*');
if (star) {
*star = '\0';
}
char* fields[32] = {0};
int count = splitCsvPreserveEmpty(line, fields, 32);
if (count <= 0 || !fields[0]) {
return;
}
if (strcmp(fields[0], "$PUBX") == 0) {
m_seenUbloxPubx = true;
strlcpy(m_detectedChip, "MAX-M10S", sizeof(m_detectedChip));
return;
}
size_t n = strlen(fields[0]);
if (n < 6) {
return;
}
const char* type = fields[0] + (n - 3);
if (strcmp(type, "GGA") == 0) {
parseGga(fields, count);
} else if (strcmp(type, "GSA") == 0) {
parseGsa(fields, count);
} else if (strcmp(type, "GSV") == 0) {
parseGsv(fields, count);
} else if (strcmp(type, "RMC") == 0) {
parseRmc(fields, count);
} else if (strcmp(type, "VTG") == 0) {
parseVtg(fields, count);
} else if (strcmp(type, "TXT") == 0) {
parseTxt(fields, count);
}
}
void GnssManager::poll() {
#ifdef GPS_1PPS_PIN
m_hasPps = (digitalRead(GPS_1PPS_PIN) == HIGH);
#endif
while (m_serial.available() > 0) {
char c = (char)m_serial.read();
if (c == '\r') {
continue;
}
if (c == '\n') {
if (m_lineLen > 0) {
m_line[m_lineLen] = '\0';
processNmeaLine(m_line);
m_lineLen = 0;
}
continue;
}
if (m_lineLen + 1 < sizeof(m_line)) {
m_line[m_lineLen++] = c;
} else {
m_lineLen = 0;
}
}
}
GnssSample GnssManager::makeSample() const {
GnssSample sample = m_state;
sample.ppsSeen = m_hasPps;
sample.sampleMillis = millis();
if (m_lastFixMs > 0) {
sample.ageOfFixMs = millis() - m_lastFixMs;
}
sample.ttffMs = (m_lastFixMs > 0) ? (m_lastFixMs - m_bootMs) : 0;
if (sample.fixType == FixType::NoFix) {
if (sample.fixDimension >= 3) {
sample.fixType = FixType::Fix3D;
} else if (sample.fixDimension == 2) {
sample.fixType = FixType::Fix2D;
}
}
return sample;
}
size_t GnssManager::copySatellites(SatelliteInfo* out, size_t maxCount) const {
if (!out || maxCount == 0) {
return 0;
}
size_t n = m_satCount < maxCount ? m_satCount : maxCount;
for (size_t i = 0; i < n; ++i) {
out[i] = m_satellites[i];
}
return n;
}
const char* GnssManager::detectedChipName() const {
return m_detectedChip;
}
} // namespace field_qa

View file

@ -0,0 +1,54 @@
#pragma once
#include <Arduino.h>
#include "Config.h"
#include "GnssTypes.h"
namespace field_qa {
class GnssManager {
public:
void begin();
void poll();
bool probeAtStartup(Stream& serialOut);
GnssSample makeSample() const;
size_t copySatellites(SatelliteInfo* out, size_t maxCount) const;
const char* detectedChipName() const;
private:
void startUart(uint32_t baud, int rxPin, int txPin);
bool probeAtBaud(uint32_t baud, int rxPin, int txPin);
bool collectTraffic(uint32_t windowMs);
void processNmeaLine(char* line);
void parseGga(char* fields[], int count);
void parseGsa(char* fields[], int count);
void parseGsv(char* fields[], int count);
void parseRmc(char* fields[], int count);
void parseVtg(char* fields[], int count);
void parseTxt(char* fields[], int count);
int splitCsvPreserveEmpty(char* line, char* fields[], int maxFields);
static bool parseUInt2(const char* s, uint8_t& out);
static double parseNmeaCoord(const char* value, const char* hemi);
void clearSatelliteView();
void finalizeSatelliteStats();
bool prnUsedInSolution(uint8_t prn) const;
HardwareSerial m_serial{1};
char m_line[160] = {0};
size_t m_lineLen = 0;
char m_detectedChip[16] = {0};
bool m_sawSentence = false;
bool m_seenUbloxPubx = false;
bool m_hasPps = false;
GnssSample m_state;
SatelliteInfo m_satellites[kMaxSatellites];
uint8_t m_usedPrns[16] = {0};
size_t m_usedPrnCount = 0;
size_t m_satCount = 0;
uint32_t m_lastGsvMs = 0;
uint32_t m_lastFixMs = 0;
uint32_t m_bootMs = 0;
};
} // namespace field_qa

View file

@ -0,0 +1,41 @@
#include "GnssTypes.h"
#include "Config.h"
namespace field_qa {
const char* fixTypeToString(FixType type) {
switch (type) {
case FixType::Fix2D:
return "2D";
case FixType::Fix3D:
return "3D";
case FixType::Dgps:
return "DGPS";
case FixType::RtkFloat:
return "RTK_FLOAT";
case FixType::RtkFixed:
return "RTK_FIXED";
case FixType::NoFix:
default:
return "NO_FIX";
}
}
const char* qualityClassForSample(const GnssSample& sample) {
if (!sample.validFix || sample.fixDimension < 2 || sample.satsUsed < (int)kPoorMinSatsUsed ||
(!sample.validHdop && sample.fixDimension < 3)) {
return "POOR";
}
if (sample.fixDimension < 3 || sample.satsUsed < (int)kGoodMinSatsUsed ||
(sample.validHdop && sample.hdop >= kMarginalHdop)) {
return "MARGINAL";
}
if (sample.fixDimension >= 3 && sample.satsUsed >= (int)kExcellentMinSatsUsed &&
sample.validHdop && sample.hdop < kExcellentHdop) {
return "EXCELLENT";
}
return "GOOD";
}
} // namespace field_qa

View file

@ -0,0 +1,78 @@
#pragma once
#include <Arduino.h>
namespace field_qa {
enum class FixType : uint8_t {
NoFix = 0,
Fix2D,
Fix3D,
Dgps,
RtkFloat,
RtkFixed
};
struct SatelliteInfo {
bool valid = false;
bool usedInSolution = false;
char talker[3] = {'?', '?', '\0'};
uint8_t prn = 0;
uint8_t elevation = 0;
uint16_t azimuth = 0;
uint8_t snr = 0;
};
struct GnssSample {
bool sawSentence = false;
bool validTime = false;
bool validFix = false;
bool validLocation = false;
bool validAltitude = false;
bool validCourse = false;
bool validSpeed = false;
bool validHdop = false;
bool validVdop = false;
bool validPdop = false;
bool ppsSeen = false;
FixType fixType = FixType::NoFix;
int fixDimension = 0;
int satsInView = -1;
int satsUsed = -1;
float hdop = -1.0f;
float vdop = -1.0f;
float pdop = -1.0f;
double latitude = 0.0;
double longitude = 0.0;
double altitudeM = 0.0;
float speedMps = -1.0f;
float courseDeg = -1.0f;
uint16_t year = 0;
uint8_t month = 0;
uint8_t day = 0;
uint8_t hour = 0;
uint8_t minute = 0;
uint8_t second = 0;
uint8_t gpsCount = 0;
uint8_t galileoCount = 0;
uint8_t glonassCount = 0;
uint8_t beidouCount = 0;
uint8_t navicCount = 0;
uint8_t qzssCount = 0;
uint8_t sbasCount = 0;
float meanSnr = -1.0f;
uint8_t maxSnr = 0;
uint32_t ageOfFixMs = 0;
uint32_t ttffMs = 0;
uint32_t longestNoFixMs = 0;
uint32_t sampleMillis = 0;
};
const char* fixTypeToString(FixType type);
const char* qualityClassForSample(const GnssSample& sample);
} // namespace field_qa

View file

@ -0,0 +1,53 @@
#include "RunStats.h"
namespace field_qa {
void RunStats::begin(uint32_t nowMs) {
m_bootMs = nowMs;
m_noFixStartMs = nowMs;
m_longestNoFixMs = 0;
m_ttffMs = 0;
m_started = true;
m_haveFirstFix = false;
}
void RunStats::updateFromSample(const GnssSample& sample, uint32_t nowMs) {
if (!m_started) {
begin(nowMs);
}
if (sample.validFix) {
if (!m_haveFirstFix) {
m_ttffMs = nowMs - m_bootMs;
m_haveFirstFix = true;
}
if (m_noFixStartMs != 0) {
uint32_t noFixMs = nowMs - m_noFixStartMs;
if (noFixMs > m_longestNoFixMs) {
m_longestNoFixMs = noFixMs;
}
m_noFixStartMs = 0;
}
} else if (m_noFixStartMs == 0) {
m_noFixStartMs = nowMs;
}
}
uint32_t RunStats::elapsedMs(uint32_t nowMs) const {
return m_started ? (nowMs - m_bootMs) : 0;
}
uint32_t RunStats::longestNoFixMs() const {
return m_longestNoFixMs;
}
uint32_t RunStats::ttffMs() const {
return m_ttffMs;
}
bool RunStats::hasFirstFix() const {
return m_haveFirstFix;
}
} // namespace field_qa

View file

@ -0,0 +1,27 @@
#pragma once
#include <Arduino.h>
#include "GnssTypes.h"
namespace field_qa {
class RunStats {
public:
void begin(uint32_t nowMs);
void updateFromSample(const GnssSample& sample, uint32_t nowMs);
uint32_t elapsedMs(uint32_t nowMs) const;
uint32_t longestNoFixMs() const;
uint32_t ttffMs() const;
bool hasFirstFix() const;
private:
uint32_t m_bootMs = 0;
uint32_t m_noFixStartMs = 0;
uint32_t m_longestNoFixMs = 0;
uint32_t m_ttffMs = 0;
bool m_started = false;
bool m_haveFirstFix = false;
};
} // namespace field_qa

View file

@ -0,0 +1,611 @@
#include "StorageManager.h"
#include "Config.h"
#include "GnssTypes.h"
namespace field_qa {
namespace {
static constexpr char kLogFieldDelimiter = ',';
static bool isRecognizedLogName(const String& name) {
return name.endsWith(".csv") || name.endsWith(".tsv");
}
static String formatFloat(float value, bool valid, uint8_t decimals = 1) {
if (!valid) {
return "";
}
return String(value, (unsigned int)decimals);
}
static String formatDouble(double value, bool valid, uint8_t decimals = 6) {
if (!valid) {
return "";
}
return String(value, (unsigned int)decimals);
}
static String sampleTimestamp(const GnssSample& sample) {
if (!sample.validTime) {
return "";
}
char buf[24];
snprintf(buf,
sizeof(buf),
"%04u-%02u-%02uT%02u:%02u:%02uZ",
(unsigned)sample.year,
(unsigned)sample.month,
(unsigned)sample.day,
(unsigned)sample.hour,
(unsigned)sample.minute,
(unsigned)sample.second);
return String(buf);
}
static const char* constellationForTalker(const char* talker) {
if (!talker) return "UNKNOWN";
if (strcmp(talker, "GP") == 0 || strcmp(talker, "GN") == 0) return "GPS";
if (strcmp(talker, "GA") == 0) return "GALILEO";
if (strcmp(talker, "GL") == 0) return "GLONASS";
if (strcmp(talker, "GB") == 0 || strcmp(talker, "BD") == 0) return "BEIDOU";
if (strcmp(talker, "GI") == 0) return "NAVIC";
if (strcmp(talker, "GQ") == 0) return "QZSS";
if (strcmp(talker, "GS") == 0) return "SBAS";
return "UNKNOWN";
}
} // namespace
bool StorageManager::startLog(const char* runId, const char* bootTimestampUtc) {
close();
m_ready = false;
m_lastError = "";
m_path = makeFilePath(runId);
m_newFile = !SD.exists(m_path.c_str());
if (!ensureDir() || !openFile()) {
return false;
}
m_ready = true;
writeHeader(runId, bootTimestampUtc);
return true;
}
bool StorageManager::mounted() const {
File root = SD.open("/", FILE_READ);
const bool ok = root && root.isDirectory();
root.close();
return ok;
}
bool StorageManager::ready() const {
return m_ready;
}
const char* StorageManager::currentPath() const {
return m_path.c_str();
}
const char* StorageManager::lastError() const {
return m_lastError.c_str();
}
bool StorageManager::fileOpen() const {
return (bool)m_file;
}
size_t StorageManager::bufferedBytes() const {
return m_bufferLengths[0] + m_bufferLengths[1];
}
size_t StorageManager::countLogsRecursive(const char* path) const {
File dir = SD.open(path, FILE_READ);
if (!dir || !dir.isDirectory()) {
dir.close();
return 0;
}
size_t count = 0;
File entry = dir.openNextFile();
while (entry) {
String name = entry.name();
if (entry.isDirectory()) {
count += countLogsRecursive(name.c_str());
} else if (isRecognizedLogName(name)) {
++count;
}
entry.close();
entry = dir.openNextFile();
}
dir.close();
return count;
}
size_t StorageManager::logFileCount() const {
return countLogsRecursive(kLogDir);
}
bool StorageManager::ensureDir() {
String full(kLogDir);
if (!full.startsWith("/")) {
full = "/" + full;
}
int start = 1;
while (start > 0 && start < (int)full.length()) {
const 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())) {
m_lastError = "SD.mkdir failed";
return false;
}
if (slash < 0) {
break;
}
start = slash + 1;
}
return true;
}
String StorageManager::makeFilePath(const char* runId) const {
char basePath[96];
char candidatePath[112];
const char* rid = (runId && runId[0] != '\0') ? runId : "run";
snprintf(basePath, sizeof(basePath), "%s/%s", kLogDir, rid);
snprintf(candidatePath, sizeof(candidatePath), "%s.csv", basePath);
if (!SD.exists(candidatePath)) {
return String(candidatePath);
}
for (uint16_t suffix = 2; suffix < 1000; ++suffix) {
snprintf(candidatePath, sizeof(candidatePath), "%s_%02u.csv", basePath, (unsigned)suffix);
if (!SD.exists(candidatePath)) {
return String(candidatePath);
}
}
snprintf(candidatePath, sizeof(candidatePath), "%s_overflow.csv", basePath);
return String(candidatePath);
}
bool StorageManager::openFile() {
m_file = SD.open(m_path.c_str(), FILE_WRITE);
if (!m_file) {
m_lastError = "SD.open write failed";
return false;
}
return true;
}
void StorageManager::writeHeader(const char* runId, const char* bootTimestampUtc) {
if (!m_file || !m_newFile) {
return;
}
m_file.printf("# exercise: %s\n", kExerciseName);
m_file.printf("# version: %s\n", kFirmwareVersion);
m_file.printf("# board_id: %s\n", kBoardId);
m_file.printf("# gnss_chip: %s\n", kGnssChip);
m_file.printf("# storage: %s\n", kStorageName);
m_file.printf("# sample_period_ms: %lu\n", (unsigned long)kSamplePeriodMs);
m_file.printf("# log_period_ms: %lu\n", (unsigned long)kLogFlushPeriodMs);
m_file.printf("# run_id: %s\n", runId ? runId : "");
m_file.printf("# boot_timestamp_utc: %s\n", bootTimestampUtc ? bootTimestampUtc : "");
m_file.printf("# created_by: ChatGPT/Codex handoff\n");
m_file.print("record_type,timestamp_utc,sample_seq,ms_since_run_start,board_id,gnss_chip,firmware_exercise_name,firmware_version,boot_timestamp_utc,run_id,fix_type,fix_dimension,sats_in_view,sat_seen,sats_used,hdop,vdop,pdop,latitude,longitude,altitude_m,speed_mps,course_deg,pps_seen,quality_class,gps_count,galileo_count,glonass_count,beidou_count,navic_count,qzss_count,sbas_count,mean_cn0,max_cn0,age_of_fix_ms,ttff_ms,longest_no_fix_ms,sat_talker,sat_constellation,sat_prn,sat_elevation_deg,sat_azimuth_deg,sat_snr,sat_used_in_solution\n");
m_file.flush();
m_newFile = false;
}
bool StorageManager::writePendingBuffer() {
if (!m_file) {
return false;
}
for (uint8_t i = 0; i < 2; ++i) {
if (!m_bufferPending[i] || m_bufferLengths[i] == 0) {
continue;
}
const size_t wrote = m_file.write((const uint8_t*)m_buffers[i], m_bufferLengths[i]);
if (wrote != m_bufferLengths[i]) {
m_lastError = "SD.write failed";
m_ready = false;
return false;
}
m_bufferLengths[i] = 0;
m_bufferPending[i] = false;
}
return true;
}
bool StorageManager::appendBytes(const char* data, size_t len) {
if (!m_file || !data || len == 0) {
return false;
}
if (len > kStorageBufferBytes) {
if (!writePendingBuffer()) {
return false;
}
const size_t wrote = m_file.write((const uint8_t*)data, len);
if (wrote != len) {
m_lastError = "SD.write large block failed";
m_ready = false;
return false;
}
return true;
}
if ((m_bufferLengths[m_activeBuffer] + len) > kStorageBufferBytes) {
m_bufferPending[m_activeBuffer] = true;
m_activeBuffer ^= 1U;
if (m_bufferPending[m_activeBuffer]) {
if (!writePendingBuffer()) {
return false;
}
}
if (m_bufferLengths[m_activeBuffer] != 0) {
m_bufferPending[m_activeBuffer] = true;
if (!writePendingBuffer()) {
return false;
}
}
}
memcpy(m_buffers[m_activeBuffer] + m_bufferLengths[m_activeBuffer], data, len);
m_bufferLengths[m_activeBuffer] += len;
return true;
}
bool StorageManager::appendLine(const String& line) {
if (line.endsWith("\n")) {
return appendBytes(line.c_str(), line.length());
}
String record = line;
record += '\n';
return appendBytes(record.c_str(), record.length());
}
void StorageManager::appendSampleCsv(const GnssSample& sample,
uint32_t sampleSeq,
uint32_t msSinceRunStart,
const char* runId,
const char* bootTimestampUtc) {
if (!m_file) {
return;
}
if (m_file.size() == 0) {
writeHeader(runId, bootTimestampUtc);
}
String line = "sample,";
line += sampleTimestamp(sample);
line += kLogFieldDelimiter;
line += String(sampleSeq);
line += kLogFieldDelimiter;
line += String(msSinceRunStart);
line += kLogFieldDelimiter;
line += kBoardId;
line += kLogFieldDelimiter;
line += kGnssChip;
line += kLogFieldDelimiter;
line += kExerciseName;
line += kLogFieldDelimiter;
line += kFirmwareVersion;
line += kLogFieldDelimiter;
line += (bootTimestampUtc ? bootTimestampUtc : "");
line += kLogFieldDelimiter;
line += (runId ? runId : "");
line += kLogFieldDelimiter;
line += fixTypeToString(sample.fixType);
line += kLogFieldDelimiter;
line += String(sample.fixDimension);
line += kLogFieldDelimiter;
line += (sample.satsInView >= 0 ? String(sample.satsInView) : "");
line += kLogFieldDelimiter;
line += (sample.satsInView >= 0 ? String(sample.satsInView) : "");
line += kLogFieldDelimiter;
line += (sample.satsUsed >= 0 ? String(sample.satsUsed) : "");
line += kLogFieldDelimiter;
line += formatFloat(sample.hdop, sample.validHdop);
line += kLogFieldDelimiter;
line += formatFloat(sample.vdop, sample.validVdop);
line += kLogFieldDelimiter;
line += formatFloat(sample.pdop, sample.validPdop);
line += kLogFieldDelimiter;
line += formatDouble(sample.latitude, sample.validLocation);
line += kLogFieldDelimiter;
line += formatDouble(sample.longitude, sample.validLocation);
line += kLogFieldDelimiter;
line += formatDouble(sample.altitudeM, sample.validAltitude, 2);
line += kLogFieldDelimiter;
line += formatFloat(sample.speedMps, sample.validSpeed, 2);
line += kLogFieldDelimiter;
line += formatFloat(sample.courseDeg, sample.validCourse, 1);
line += kLogFieldDelimiter;
line += sample.ppsSeen ? "1" : "0";
line += kLogFieldDelimiter;
line += qualityClassForSample(sample);
line += kLogFieldDelimiter;
line += String(sample.gpsCount);
line += kLogFieldDelimiter;
line += String(sample.galileoCount);
line += kLogFieldDelimiter;
line += String(sample.glonassCount);
line += kLogFieldDelimiter;
line += String(sample.beidouCount);
line += kLogFieldDelimiter;
line += String(sample.navicCount);
line += kLogFieldDelimiter;
line += String(sample.qzssCount);
line += kLogFieldDelimiter;
line += String(sample.sbasCount);
line += kLogFieldDelimiter;
line += formatFloat(sample.meanSnr, sample.meanSnr >= 0.0f, 1);
line += kLogFieldDelimiter;
line += (sample.maxSnr > 0 ? String(sample.maxSnr) : "");
line += kLogFieldDelimiter;
line += String(sample.ageOfFixMs);
line += kLogFieldDelimiter;
line += String(sample.ttffMs);
line += kLogFieldDelimiter;
line += String(sample.longestNoFixMs);
line += ",,,,,,,";
(void)appendLine(line);
}
void StorageManager::appendSatelliteCsv(const GnssSample& sample,
uint32_t sampleSeq,
uint32_t msSinceRunStart,
const SatelliteInfo* satellites,
size_t satelliteCount,
const char* runId,
const char* bootTimestampUtc) {
if (!satellites || satelliteCount == 0 || !m_file) {
return;
}
if (m_file.size() == 0) {
writeHeader(runId, bootTimestampUtc);
}
for (size_t i = 0; i < satelliteCount; ++i) {
const SatelliteInfo& sat = satellites[i];
if (!sat.valid) {
continue;
}
String line = "satellite,";
line += sampleTimestamp(sample);
line += kLogFieldDelimiter;
line += String(sampleSeq);
line += kLogFieldDelimiter;
line += String(msSinceRunStart);
line += kLogFieldDelimiter;
line += kBoardId;
line += kLogFieldDelimiter;
line += kGnssChip;
line += kLogFieldDelimiter;
line += kExerciseName;
line += kLogFieldDelimiter;
line += kFirmwareVersion;
line += kLogFieldDelimiter;
line += (bootTimestampUtc ? bootTimestampUtc : "");
line += kLogFieldDelimiter;
line += (runId ? runId : "");
line += kLogFieldDelimiter;
line += fixTypeToString(sample.fixType);
line += kLogFieldDelimiter;
line += String(sample.fixDimension);
line += kLogFieldDelimiter;
line += (sample.satsInView >= 0 ? String(sample.satsInView) : "");
line += kLogFieldDelimiter;
line += (sample.satsInView >= 0 ? String(sample.satsInView) : "");
line += kLogFieldDelimiter;
line += (sample.satsUsed >= 0 ? String(sample.satsUsed) : "");
line += kLogFieldDelimiter;
line += formatFloat(sample.hdop, sample.validHdop);
line += kLogFieldDelimiter;
line += formatFloat(sample.vdop, sample.validVdop);
line += kLogFieldDelimiter;
line += formatFloat(sample.pdop, sample.validPdop);
line += kLogFieldDelimiter;
line += formatDouble(sample.latitude, sample.validLocation);
line += kLogFieldDelimiter;
line += formatDouble(sample.longitude, sample.validLocation);
line += kLogFieldDelimiter;
line += formatDouble(sample.altitudeM, sample.validAltitude, 2);
line += kLogFieldDelimiter;
line += formatFloat(sample.speedMps, sample.validSpeed, 2);
line += kLogFieldDelimiter;
line += formatFloat(sample.courseDeg, sample.validCourse, 1);
line += kLogFieldDelimiter;
line += sample.ppsSeen ? "1" : "0";
line += kLogFieldDelimiter;
line += qualityClassForSample(sample);
line += kLogFieldDelimiter;
line += String(sample.gpsCount);
line += kLogFieldDelimiter;
line += String(sample.galileoCount);
line += kLogFieldDelimiter;
line += String(sample.glonassCount);
line += kLogFieldDelimiter;
line += String(sample.beidouCount);
line += kLogFieldDelimiter;
line += String(sample.navicCount);
line += kLogFieldDelimiter;
line += String(sample.qzssCount);
line += kLogFieldDelimiter;
line += String(sample.sbasCount);
line += kLogFieldDelimiter;
line += formatFloat(sample.meanSnr, sample.meanSnr >= 0.0f, 1);
line += kLogFieldDelimiter;
line += (sample.maxSnr > 0 ? String(sample.maxSnr) : "");
line += kLogFieldDelimiter;
line += String(sample.ageOfFixMs);
line += kLogFieldDelimiter;
line += String(sample.ttffMs);
line += kLogFieldDelimiter;
line += String(sample.longestNoFixMs);
line += kLogFieldDelimiter;
line += sat.talker;
line += kLogFieldDelimiter;
line += constellationForTalker(sat.talker);
line += kLogFieldDelimiter;
line += String(sat.prn);
line += kLogFieldDelimiter;
line += String(sat.elevation);
line += kLogFieldDelimiter;
line += String(sat.azimuth);
line += kLogFieldDelimiter;
line += String(sat.snr);
line += kLogFieldDelimiter;
line += sat.usedInSolution ? "1" : "0";
(void)appendLine(line);
}
}
void StorageManager::flush() {
if (!m_file) {
return;
}
if (m_bufferLengths[m_activeBuffer] > 0) {
m_bufferPending[m_activeBuffer] = true;
}
if (!writePendingBuffer()) {
return;
}
m_file.flush();
}
void StorageManager::close() {
flush();
if (m_file) {
m_file.close();
}
m_ready = false;
m_newFile = false;
}
bool StorageManager::normalizePath(const char* input, String& normalized) const {
normalized = "";
if (!input || input[0] == '\0') {
return false;
}
normalized = input[0] == '/' ? String(input) : (String("/") + input);
if (normalized.indexOf("..") >= 0) {
normalized = "";
return false;
}
return true;
}
void StorageManager::listFilesRecursive(File& dir, Stream& out) {
File entry = dir.openNextFile();
while (entry) {
String name = entry.name();
if (entry.isDirectory()) {
out.printf("%s/\n", name.c_str());
listFilesRecursive(entry, out);
} else if (isRecognizedLogName(name)) {
out.printf("%s\t%u\n", name.c_str(), (unsigned)entry.size());
}
entry.close();
entry = dir.openNextFile();
}
}
void StorageManager::listFiles(Stream& out) {
if (!mounted()) {
out.println("storage not mounted");
return;
}
File dir = SD.open(kLogDir, FILE_READ);
if (!dir || !dir.isDirectory()) {
out.println("log directory unavailable");
dir.close();
return;
}
listFilesRecursive(dir, out);
dir.close();
}
void StorageManager::catFile(Stream& out, const char* path) {
if (!mounted()) {
out.println("storage not mounted");
return;
}
String fullPath;
if (!normalizePath(path, fullPath)) {
out.println("cat requires a valid filename");
return;
}
File file = SD.open(fullPath.c_str(), FILE_READ);
if (!file) {
out.printf("unable to open %s\n", fullPath.c_str());
return;
}
while (file.available()) {
out.write(file.read());
}
if (file.size() > 0) {
out.println();
}
file.close();
}
void StorageManager::eraseLogsRecursive(File& dir) {
File entry = dir.openNextFile();
while (entry) {
String path = entry.name();
const bool isDir = entry.isDirectory();
entry.close();
if (isDir) {
File subdir = SD.open(path.c_str(), FILE_READ);
if (subdir) {
eraseLogsRecursive(subdir);
subdir.close();
}
} else if (isRecognizedLogName(path)) {
SD.remove(path.c_str());
}
entry = dir.openNextFile();
}
}
void StorageManager::eraseLogs(Stream& out) {
if (!mounted()) {
out.println("storage not mounted");
return;
}
File dir = SD.open(kLogDir, FILE_READ);
if (!dir || !dir.isDirectory()) {
out.println("log directory unavailable");
dir.close();
return;
}
eraseLogsRecursive(dir);
dir.close();
out.println("logs erased");
}
bool StorageManager::eraseFile(const char* path) {
String fullPath;
if (!normalizePath(path, fullPath)) {
m_lastError = "invalid path";
return false;
}
if (m_path == fullPath && m_file) {
close();
}
if (!SD.exists(fullPath.c_str())) {
m_lastError = "path not found";
return false;
}
if (!SD.remove(fullPath.c_str())) {
m_lastError = "SD.remove failed";
return false;
}
return true;
}
} // namespace field_qa

View file

@ -0,0 +1,63 @@
#pragma once
#include <Arduino.h>
#include <SD.h>
#include "Config.h"
#include "GnssTypes.h"
namespace field_qa {
class StorageManager {
public:
bool startLog(const char* runId, const char* bootTimestampUtc);
bool mounted() const;
bool ready() const;
const char* currentPath() const;
const char* lastError() const;
bool fileOpen() const;
size_t bufferedBytes() const;
size_t logFileCount() const;
void appendSampleCsv(const GnssSample& sample,
uint32_t sampleSeq,
uint32_t msSinceRunStart,
const char* runId,
const char* bootTimestampUtc);
void appendSatelliteCsv(const GnssSample& sample,
uint32_t sampleSeq,
uint32_t msSinceRunStart,
const SatelliteInfo* satellites,
size_t satelliteCount,
const char* runId,
const char* bootTimestampUtc);
void flush();
void close();
void listFiles(Stream& out);
void catFile(Stream& out, const char* path);
void eraseLogs(Stream& out);
bool eraseFile(const char* path);
bool normalizePath(const char* input, String& normalized) const;
private:
bool ensureDir();
bool openFile();
void writeHeader(const char* runId, const char* bootTimestampUtc);
String makeFilePath(const char* runId) const;
bool appendLine(const String& line);
bool appendBytes(const char* data, size_t len);
bool writePendingBuffer();
size_t countLogsRecursive(const char* path) const;
void listFilesRecursive(File& dir, Stream& out);
void eraseLogsRecursive(File& dir);
bool m_ready = false;
bool m_newFile = false;
String m_path;
String m_lastError;
File m_file;
char m_buffers[2][kStorageBufferBytes] = {};
size_t m_bufferLengths[2] = {0, 0};
bool m_bufferPending[2] = {false, false};
uint8_t m_activeBuffer = 0;
};
} // namespace field_qa

View file

@ -0,0 +1,379 @@
#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;
}
bool StartupSdManager::forceRemount() {
logf("Watcher: manual rescan requested");
presentVotes_ = 0;
absentVotes_ = 0;
lastPollMs_ = 0;
lastFullScanMs_ = millis();
cycleSdRail(cfg_.recoveryRailOffMs, cfg_.recoveryRailOnSettleMs);
delay(cfg_.startupWarmupMs);
if (mountCardFullScan()) {
setStateMounted();
return true;
}
setStateAbsent();
return false;
}
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;
}

View file

@ -0,0 +1,91 @@
#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();
bool forceRemount();
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;
};

View file

@ -0,0 +1,12 @@
{
"name": "startup_sd",
"version": "0.1.0",
"dependencies": [
{
"name": "XPowersLib"
},
{
"name": "Wire"
}
]
}

View file

@ -0,0 +1,104 @@
; 20260405 ChatGPT
; Exercise 18_GPS_Field_QA
[platformio]
default_envs = cy
[env]
platform = espressif32
framework = arduino
board = esp32-s3-devkitc-1
board_build.partitions = default_8MB.csv
monitor_speed = 115200
extra_scripts = pre:scripts/set_build_epoch.py
lib_deps =
Wire
olikraus/U8g2@^2.36.4
lewisxhe/XPowersLib@0.3.3
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 GPS_L76K
-D NODE_SLOT_COUNT=7
-D ARDUINO_USB_MODE=1
-D ARDUINO_USB_CDC_ON_BOOT=1
[env:amy]
extends = env
build_flags =
${env.build_flags}
-D BOARD_ID=\"AMY\"
-D NODE_LABEL=\"Amy\"
-D NODE_SHORT=\"A\"
-D NODE_SLOT_INDEX=0
-D GNSS_CHIP_NAME=\"L76K\"
[env:bob]
extends = env
build_flags =
${env.build_flags}
-D BOARD_ID=\"BOB\"
-D NODE_LABEL=\"Bob\"
-D NODE_SHORT=\"B\"
-D NODE_SLOT_INDEX=1
-D GNSS_CHIP_NAME=\"L76K\"
[env:cy]
extends = env
build_flags =
${env.build_flags}
-D BOARD_ID=\"CY\"
-D NODE_LABEL=\"Cy\"
-D NODE_SHORT=\"C\"
-D NODE_SLOT_INDEX=2
-D GNSS_CHIP_NAME=\"L76K\"
[env:dan]
extends = env
build_flags =
${env.build_flags}
-D BOARD_ID=\"DAN\"
-D NODE_LABEL=\"Dan\"
-D NODE_SHORT=\"D\"
-D NODE_SLOT_INDEX=3
-D GNSS_CHIP_NAME=\"L76K\"
[env:ed]
extends = env
build_flags =
${env.build_flags}
-D BOARD_ID=\"ED\"
-D NODE_LABEL=\"Ed\"
-D NODE_SHORT=\"E\"
-D NODE_SLOT_INDEX=4
-D GNSS_CHIP_NAME=\"L76K\"
[env:flo]
extends = env
build_flags =
${env.build_flags}
-D BOARD_ID=\"FLO\"
-D NODE_LABEL=\"Flo\"
-D NODE_SHORT=\"F\"
-D NODE_SLOT_INDEX=5
-D GNSS_CHIP_NAME=\"L76K\"
[env:guy]
extends = env
build_flags =
${env.build_flags}
-D BOARD_ID=\"GUY\"
-D NODE_LABEL=\"Guy\"
-D NODE_SHORT=\"G\"
-D NODE_SLOT_INDEX=6
-D GNSS_CHIP_NAME=\"MAX-M10S\"
-D GPS_UBLOX

View file

@ -0,0 +1,419 @@
#!/usr/bin/env perl
# 20260406 ChatGPT
# $Header$
#
# Example:
# perl import_satellite_logs.pl \
# --dbname satellite_data \
# --host localhost \
# --user jlpoole \
# --schema public \
# /path/to/20260406_175441_GUY.csv
#
# Notes:
# * Imports one or more CSV files into tables logs and log_data.
# * Preserves all leading hash-prefixed header lines in logs.raw_header_text.
# * Uses the file's own CSV header row when present.
# * When no CSV header row is present, it falls back by column count:
# - legacy schema without sample_seq/ms_since_run_start
# - enhanced schema with sample_seq/ms_since_run_start
use strict;
use warnings;
use utf8;
use DBI;
use Digest::SHA qw(sha256_hex);
use File::Basename qw(basename);
use Getopt::Long qw(GetOptions);
use Text::CSV_XS;
my @LEGACY_COLUMNS = qw(
record_type timestamp_utc board_id gnss_chip firmware_exercise_name firmware_version
boot_timestamp_utc run_id fix_type fix_dimension sats_in_view sat_seen sats_used
hdop vdop pdop latitude longitude altitude_m speed_mps course_deg pps_seen
quality_class gps_count galileo_count glonass_count beidou_count navic_count
qzss_count sbas_count mean_cn0 max_cn0 age_of_fix_ms ttff_ms longest_no_fix_ms
sat_talker sat_constellation sat_prn sat_elevation_deg sat_azimuth_deg sat_snr
sat_used_in_solution
);
my @ENHANCED_COLUMNS = qw(
record_type timestamp_utc sample_seq ms_since_run_start board_id gnss_chip
firmware_exercise_name firmware_version boot_timestamp_utc run_id
fix_type fix_dimension sats_in_view sat_seen sats_used
hdop vdop pdop latitude longitude altitude_m speed_mps course_deg pps_seen
quality_class gps_count galileo_count glonass_count beidou_count navic_count
qzss_count sbas_count mean_cn0 max_cn0 age_of_fix_ms ttff_ms longest_no_fix_ms
sat_talker sat_constellation sat_prn sat_elevation_deg sat_azimuth_deg sat_snr
sat_used_in_solution
);
my $LEGACY_HEADER = join ',', @LEGACY_COLUMNS;
my $ENHANCED_HEADER = join ',', @ENHANCED_COLUMNS;
my %opt = (
dbname => 'satellite_data',
host => 'ryzdesk',
port => 5432,
schema => 'public',
);
GetOptions(
'dbname=s' => \$opt{dbname},
'host=s' => \$opt{host},
'port=i' => \$opt{port},
'user=s' => \$opt{user},
'password=s' => \$opt{password},
'schema=s' => \$opt{schema},
'header-line=s' => \$opt{header_line},
'notes=s' => \$opt{import_notes},
'help' => \$opt{help},
) or die usage();
if ($opt{help} || !@ARGV) {
print usage();
exit 0;
}
my $dsn = sprintf('dbi:Pg:dbname=%s;host=%s;port=%d', $opt{dbname}, $opt{host}, $opt{port});
my $dbh = DBI->connect(
$dsn,
$opt{user},
$opt{password},
{
RaiseError => 1,
AutoCommit => 1,
PrintError => 0,
pg_enable_utf8 => 1,
}
) or die DBI->errstr;
$dbh->do("SET search_path TO $opt{schema}");
for my $file (@ARGV) {
import_file($dbh, $file, \%opt);
}
$dbh->disconnect;
exit 0;
#
# ------------------------- subs -----------------------------
#
#
# import_file first creates an entry in logs, gets and ID, then
# parses the data rows and inserts each row.
#
sub import_file {
my ($dbh, $file, $opt) = @_;
#
# get a fixed-length hash (fingerprint) so we do not accidently
# load the same file twice.
#
my $sha256 = "";
my $blob;
{
open my $fh, '<:raw', $file or die "Cannot open $file: $!\n";
local $/;
$blob = <$fh>;
close $fh;
}
$sha256 = sha256_hex($blob // '');
my $file_size = -s $file;
open my $in, '<:encoding(UTF-8)', $file or die "Cannot open $file: $!\n";
my @header_lines;
my $csv_header_line;
my @data_lines;
my $line_count = 0;
while (my $line = <$in>) {
chomp $line;
$line =~ s/\r//g; # might be there are multiple \rs!
next if $line =~ /^\s*$/ && !@data_lines && !defined $csv_header_line && !@header_lines;
$line_count++;
print "B Processing $line_count\n";
if ($line =~ /^#/) {
push @header_lines, $line;
next;
}
# record_type is the first entry in the column heading
if (!defined $csv_header_line && $line =~ /^record_type,/) {
$csv_header_line = $line;
next;
}
push @data_lines, $line;
}
close $in;
die "No CSV data rows found in $file\n" if !@data_lines;
if (!defined $csv_header_line) {
if (defined $opt->{header_line}) {
$csv_header_line = $opt->{header_line};
}
else {
my $count = count_csv_fields($data_lines[0]);
if ($count == scalar(@ENHANCED_COLUMNS)) {
$csv_header_line = $ENHANCED_HEADER;
}
elsif ($count == scalar(@LEGACY_COLUMNS)) {
$csv_header_line = $LEGACY_HEADER;
}
else {
die sprintf(
"Unable to infer header for %s: first data row has %d fields, expected %d (legacy) or %d (enhanced).\n",
$file,
$count,
scalar(@LEGACY_COLUMNS),
scalar(@ENHANCED_COLUMNS),
);
}
}
}
my @columns = parse_header_columns($csv_header_line);
my %allowed = map { $_ => 1 } qw(
record_type timestamp_utc board_id gnss_chip firmware_exercise_name firmware_version
boot_timestamp_utc run_id sample_seq ms_since_run_start fix_type fix_dimension
sats_in_view sat_seen sats_used hdop vdop pdop latitude longitude altitude_m
speed_mps course_deg pps_seen quality_class gps_count galileo_count glonass_count
beidou_count navic_count qzss_count sbas_count mean_cn0 max_cn0 age_of_fix_ms
ttff_ms longest_no_fix_ms sat_talker sat_constellation sat_prn sat_elevation_deg
sat_azimuth_deg sat_snr sat_used_in_solution
);
my $col_count = 0;
for my $col (@columns) {
$col_count++;
die "Unexpected column at column \# $col_count \"$col\" in $file\nHeader line: $csv_header_line\n"
if !$allowed{$col};
}
my $raw_header_text = join("\n", @header_lines);
$raw_header_text .= "\n" if length $raw_header_text;
my $insert_log_sql = <<'SQL';
INSERT INTO logs (
source_filename,
source_path,
file_sha256,
file_size_bytes,
raw_header_text,
csv_header_line,
import_notes
) VALUES (?, ?, ?, ?, ?, ?, ?)
RETURNING log_id
SQL
my ($log_id) = $dbh->selectrow_array(
$insert_log_sql,
undef,
basename($file),
$file,
$sha256,
$file_size,
$raw_header_text,
$csv_header_line,
$opt->{import_notes},
);
my @insert_columns = (
'log_id', 'source_row_number', @columns, 'raw_csv_line'
);
my $placeholders = join ', ', ('?') x @insert_columns;
my $insert_sql = sprintf(
'INSERT INTO log_data (%s) VALUES (%s)',
join(', ', @insert_columns),
$placeholders,
);
my $csv = Text::CSV_XS->new({
binary => 1,
auto_diag => 1,
allow_loose_quotes => 1,
allow_loose_escapes => 1,
blank_is_undef => 0,
});
my $sth = $dbh->prepare($insert_sql);
my ($row_count, $sample_count, $satellite_count) = (0, 0, 0);
my ($first_ts, $last_ts, $board_id, $gnss_chip, $fw_name, $fw_ver, $boot_ts, $run_id);
$dbh->begin_work;
$line_count = 0; # reset
for my $i (0 .. $#data_lines) {
my $line = $data_lines[$i];
next if $line =~ /^\s*$/; # empty lines
$line_count++;
$csv->parse($line) or die "CSV parse failed in $file line @{[$i+1]}: " . $csv->error_diag . "\n";
my @fields = $csv->fields;
#
# check for empty rows (possibly introduced during repair editing in LibreOffice Calc
#
my $all_empty = 1;
for my $field (@fields) {
if (defined $field && $field ne '') {
$all_empty = 0;
last;
}
}
if ($all_empty){
warn "Found empty row at $line_count and skipping";
next;
}
if (@fields != @columns) {
die sprintf(
"Column mismatch in %s data row %d: got %d fields, expected %d\nLine: %s\n",
$file, $i + 1, scalar(@fields), scalar(@columns), $line
);
}
my %row;
@row{@columns} = @fields;
normalize_row(\%row);
my $record_type = $row{record_type} // '';
$sample_count++ if $record_type eq 'sample';
$satellite_count++ if $record_type eq 'satellite';
$row_count++;
$first_ts //= $row{timestamp_utc};
$last_ts = $row{timestamp_utc} if defined $row{timestamp_utc};
$board_id //= $row{board_id};
$gnss_chip //= $row{gnss_chip};
$fw_name //= $row{firmware_exercise_name};
$fw_ver //= $row{firmware_version};
$boot_ts //= $row{boot_timestamp_utc};
$run_id //= $row{run_id};
my @values = (
$log_id,
$i + 1,
(map { $row{$_} } @columns),
$line,
);
eval {
$sth->execute(@values) or die "Line: $line_count ".$DBD::errstr;
};
if ($@){
print "[DEBUG ".__LINE__." ] i:$i\n";
die "Killed as error was found: $@";
}
}
#die "halted before commit, but after all rows processed";
$dbh->commit;
print "After commit of row data, about to update logs entry.\n";
my $update_sql = <<'SQL';
UPDATE logs
SET board_id = ?,
gnss_chip = ?,
firmware_exercise_name = ?,
firmware_version = ?,
boot_timestamp_utc = ?,
run_id = ?,
first_timestamp_utc = ?,
last_timestamp_utc = ?,
row_count = ?,
sample_count = ?,
satellite_count = ?
WHERE log_id = ?
SQL
$dbh->do(
$update_sql,
undef,
$board_id,
$gnss_chip,
$fw_name,
$fw_ver,
$boot_ts,
$run_id,
$first_ts,
$last_ts,
$row_count,
$sample_count,
$satellite_count,
$log_id,
);
print "Imported $file => log_id=$log_id rows=$row_count samples=$sample_count satellites=$satellite_count\n";
}
sub parse_header_columns {
my ($line) = @_;
#print "DEBUG [".__LINE__."] header line = $line\n";
my $csv = Text::CSV_XS->new({ binary => 1, auto_diag => 1 });
$csv->parse($line) or die "Cannot parse header line: " . $csv->error_diag . "\n";
my @cols = $csv->fields;
#print "DEBUG [".__LINE__."] columns found: ".@cols."\n";
s/^\s+|\s+$//g for @cols;
return @cols;
}
sub count_csv_fields {
my ($line) = @_;
my $csv = Text::CSV_XS->new({ binary => 1, auto_diag => 1 });
$csv->parse($line) or die "Cannot parse first data row while inferring header: " . $csv->error_diag . "\n";
my @fields = $csv->fields;
return scalar @fields;
}
sub normalize_row {
my ($row) = @_;
for my $key (keys %{$row}) {
next if !defined $row->{$key};
$row->{$key} =~ s/^\s+//;
$row->{$key} =~ s/\s+$//;
$row->{$key} = undef if $row->{$key} eq '';
}
for my $bool_key (qw(pps_seen sat_used_in_solution)) {
next if !exists $row->{$bool_key};
next if !defined $row->{$bool_key};
if ($row->{$bool_key} =~ /^(?:1|true|t|yes|y)$/i) {
$row->{$bool_key} = 'true';
}
elsif ($row->{$bool_key} =~ /^(?:0|false|f|no|n)$/i) {
$row->{$bool_key} = 'false';
}
}
}
sub usage {
return <<'USAGE';
Usage:
perl import_satellite_logs.pl [options] file1.csv [file2.csv ...]
Options:
--dbname NAME Database name. Default: satellite_data
--host HOST PostgreSQL host. Default: localhost
--port PORT PostgreSQL port. Default: 5432
--user USER PostgreSQL user name
--password PASS PostgreSQL password
--schema NAME Schema name. Default: public
--header-line LINE Override the CSV header line when the file lacks one
--notes TEXT Optional import note stored in logs.import_notes
--help Show this help
Examples:
createdb satellite_data
psql -d satellite_data -f satellite_data_schema.sql
perl import_satellite_logs.pl \
--dbname satellite_data \
--host localhost \
--user jlpoole \
/path/to/20260406_175441_GUY.csv
USAGE
}

View file

@ -0,0 +1,13 @@
import time
Import("env")
epoch = int(time.time())
utc_tag = time.strftime("%Y%m%d_%H%M%S_z", time.gmtime(epoch))
env.Append(
CPPDEFINES=[
("FW_BUILD_EPOCH", str(epoch)),
("FW_BUILD_UTC", '\"%s\"' % utc_tag),
]
)

View file

@ -0,0 +1,270 @@
-- 20260406 ChatGPT
-- $Header$
--
-- Example:
-- createdb satellite_data
-- psql -d satellite_data -f satellite_data_schema.sql
--
-- Purpose:
-- Schema for importing GNSS field QA CSV logs generated by T-Beam units.
-- A log file is recorded in table logs, and each CSV row is stored in
-- table log_data with a foreign-key reference back to logs.
--
-- Notes:
-- This revision adds support for the enhanced logger fields:
-- * sample_seq
-- * ms_since_run_start
-- The importer can still load older files that do not contain those fields.
BEGIN;
CREATE TABLE IF NOT EXISTS logs (
log_id bigserial PRIMARY KEY,
source_filename text NOT NULL,
source_path text,
file_sha256 text,
file_size_bytes bigint,
raw_header_text text,
csv_header_line text NOT NULL,
imported_at timestamptz NOT NULL DEFAULT now(),
import_notes text,
board_id text,
gnss_chip text,
firmware_exercise_name text,
firmware_version text,
boot_timestamp_utc timestamptz,
run_id text,
first_timestamp_utc timestamptz,
last_timestamp_utc timestamptz,
row_count integer NOT NULL DEFAULT 0,
sample_count integer NOT NULL DEFAULT 0,
satellite_count integer NOT NULL DEFAULT 0,
CONSTRAINT logs_source_filename_key UNIQUE (source_filename, file_sha256)
);
COMMENT ON TABLE logs IS
'One row per imported CSV log file. Stores file provenance, hash, raw hash-prefixed header text, CSV header line, and summary counts.';
COMMENT ON COLUMN logs.log_id IS
'Primary key for this imported file.';
COMMENT ON COLUMN logs.source_filename IS
'Filename of the imported CSV file, e.g. 20260406_175441_GUY.csv.';
COMMENT ON COLUMN logs.source_path IS
'Path used at import time. Useful for provenance when files are staged from different directories.';
COMMENT ON COLUMN logs.file_sha256 IS
'SHA-256 digest of the source file. Helps prevent duplicate imports and supports provenance audits.';
COMMENT ON COLUMN logs.file_size_bytes IS
'Size of the source file in bytes.';
COMMENT ON COLUMN logs.raw_header_text IS
'All leading hash-prefixed lines from the file, preserved verbatim as a text block.';
COMMENT ON COLUMN logs.csv_header_line IS
'Effective CSV column header line used by the importer, either from the file or from importer fallback logic.';
COMMENT ON COLUMN logs.imported_at IS
'Timestamp when the file was imported into PostgreSQL.';
COMMENT ON COLUMN logs.import_notes IS
'Optional free-form notes supplied at import time.';
COMMENT ON COLUMN logs.board_id IS
'Board identifier observed in the file, e.g. GUY, AMY, or CY.';
COMMENT ON COLUMN logs.gnss_chip IS
'GNSS receiver chip or module name, e.g. MAX-M10S or L76K.';
COMMENT ON COLUMN logs.firmware_exercise_name IS
'Firmware exercise or logger program name that produced the file.';
COMMENT ON COLUMN logs.firmware_version IS
'Firmware build or version string written by the device.';
COMMENT ON COLUMN logs.boot_timestamp_utc IS
'UTC timestamp representing when the device booted, as reported by the firmware.';
COMMENT ON COLUMN logs.run_id IS
'Run identifier shared by all rows from one logger session.';
COMMENT ON COLUMN logs.first_timestamp_utc IS
'First UTC sample timestamp found in this file.';
COMMENT ON COLUMN logs.last_timestamp_utc IS
'Last UTC sample timestamp found in this file.';
COMMENT ON COLUMN logs.row_count IS
'Total number of imported CSV data rows in the file.';
COMMENT ON COLUMN logs.sample_count IS
'Number of imported rows where record_type = sample.';
COMMENT ON COLUMN logs.satellite_count IS
'Number of imported rows where record_type = satellite.';
CREATE TABLE IF NOT EXISTS log_data (
log_data_id bigserial PRIMARY KEY,
log_id bigint NOT NULL REFERENCES logs(log_id) ON DELETE CASCADE,
source_row_number integer NOT NULL,
record_type text NOT NULL,
timestamp_utc timestamptz,
board_id text,
gnss_chip text,
firmware_exercise_name text,
firmware_version text,
boot_timestamp_utc timestamptz,
run_id text,
sample_seq bigint,
ms_since_run_start bigint,
fix_type text,
fix_dimension integer,
sats_in_view integer,
sat_seen integer,
sats_used integer,
hdop numeric(8,3),
vdop numeric(8,3),
pdop numeric(8,3),
latitude double precision,
longitude double precision,
altitude_m numeric(12,3),
speed_mps numeric(12,3),
course_deg numeric(12,3),
pps_seen boolean,
quality_class text,
gps_count integer,
galileo_count integer,
glonass_count integer,
beidou_count integer,
navic_count integer,
qzss_count integer,
sbas_count integer,
mean_cn0 numeric(8,3),
max_cn0 numeric(8,3),
age_of_fix_ms bigint,
ttff_ms bigint,
longest_no_fix_ms bigint,
sat_talker text,
sat_constellation text,
sat_prn integer,
sat_elevation_deg numeric(8,3),
sat_azimuth_deg numeric(8,3),
sat_snr numeric(8,3),
sat_used_in_solution boolean,
raw_csv_line text,
CONSTRAINT log_data_record_type_chk CHECK (record_type IN ('sample', 'satellite'))
);
COMMENT ON TABLE log_data IS
'One row per CSV data row from a GNSS logger file. Stores both sample rows and per-satellite rows.';
COMMENT ON COLUMN log_data.log_data_id IS
'Primary key for one imported CSV data row.';
COMMENT ON COLUMN log_data.log_id IS
'Foreign key to logs.log_id, linking this row back to the source file.';
COMMENT ON COLUMN log_data.source_row_number IS
'1-based row number within the CSV data section, excluding preserved hash-prefixed header lines.';
COMMENT ON COLUMN log_data.record_type IS
'Logical row type. sample = one epoch summary row. satellite = one satellite snapshot tied to a sample epoch.';
COMMENT ON COLUMN log_data.timestamp_utc IS
'UTC time for the sample epoch, as reported by the GNSS receiver.';
COMMENT ON COLUMN log_data.board_id IS
'Board identifier such as GUY, AMY, or CY.';
COMMENT ON COLUMN log_data.gnss_chip IS
'GNSS module name, for example MAX-M10S or L76K.';
COMMENT ON COLUMN log_data.firmware_exercise_name IS
'Name of the firmware exercise or logger mode that generated the row.';
COMMENT ON COLUMN log_data.firmware_version IS
'Firmware build or version string embedded in the row.';
COMMENT ON COLUMN log_data.boot_timestamp_utc IS
'UTC timestamp representing when the device booted, according to firmware.';
COMMENT ON COLUMN log_data.run_id IS
'Run identifier shared across one logger session.';
COMMENT ON COLUMN log_data.sample_seq IS
'Sequential sample number within a run. Starts at 1 when a new log begins. Satellite rows inherit the parent sample sequence value.';
COMMENT ON COLUMN log_data.ms_since_run_start IS
'Monotonic milliseconds elapsed since the log file was opened. Useful for jitter, gap, and SD-write-impact analysis.';
COMMENT ON COLUMN log_data.fix_type IS
'Fix quality label such as NO_FIX, 2D, 3D, or DGPS depending on what the firmware emits.';
COMMENT ON COLUMN log_data.fix_dimension IS
'Numeric dimension of the position fix, typically 0, 2, or 3.';
COMMENT ON COLUMN log_data.sats_in_view IS
'Count of satellites reportedly in view at this epoch according to the receiver summary.';
COMMENT ON COLUMN log_data.sat_seen IS
'Count of satellites actually observed or emitted by the logger for this epoch. This may differ from sats_in_view depending on firmware logic.';
COMMENT ON COLUMN log_data.sats_used IS
'Count of satellites used in the navigation solution at this epoch.';
COMMENT ON COLUMN log_data.hdop IS
'Horizontal Dilution of Precision. Lower values generally indicate better horizontal geometry.';
COMMENT ON COLUMN log_data.vdop IS
'Vertical Dilution of Precision. Lower values generally indicate better vertical geometry.';
COMMENT ON COLUMN log_data.pdop IS
'Position Dilution of Precision. Combined geometry indicator for the position solution.';
COMMENT ON COLUMN log_data.latitude IS
'Latitude in decimal degrees.';
COMMENT ON COLUMN log_data.longitude IS
'Longitude in decimal degrees.';
COMMENT ON COLUMN log_data.altitude_m IS
'Altitude in meters, generally above mean sea level according to receiver output.';
COMMENT ON COLUMN log_data.speed_mps IS
'Receiver-reported speed over ground in meters per second.';
COMMENT ON COLUMN log_data.course_deg IS
'Receiver-reported course over ground in degrees.';
COMMENT ON COLUMN log_data.pps_seen IS
'Boolean indicating whether a PPS pulse was seen by the firmware during this epoch.';
COMMENT ON COLUMN log_data.quality_class IS
'Human-friendly firmware quality label such as POOR, FAIR, GOOD, or similar.';
COMMENT ON COLUMN log_data.gps_count IS
'Count of GPS satellites observed at this epoch.';
COMMENT ON COLUMN log_data.galileo_count IS
'Count of Galileo satellites observed at this epoch.';
COMMENT ON COLUMN log_data.glonass_count IS
'Count of GLONASS satellites observed at this epoch.';
COMMENT ON COLUMN log_data.beidou_count IS
'Count of BeiDou satellites observed at this epoch.';
COMMENT ON COLUMN log_data.navic_count IS
'Count of NavIC satellites observed at this epoch.';
COMMENT ON COLUMN log_data.qzss_count IS
'Count of QZSS satellites observed at this epoch.';
COMMENT ON COLUMN log_data.sbas_count IS
'Count of SBAS satellites observed at this epoch.';
COMMENT ON COLUMN log_data.mean_cn0 IS
'Mean carrier-to-noise density estimate across observed satellites. Higher values generally indicate stronger signals.';
COMMENT ON COLUMN log_data.max_cn0 IS
'Maximum carrier-to-noise density estimate among observed satellites for this epoch.';
COMMENT ON COLUMN log_data.age_of_fix_ms IS
'Age of the current fix in milliseconds, as reported by the firmware or receiver API.';
COMMENT ON COLUMN log_data.ttff_ms IS
'Time to first fix in milliseconds for the run or current acquisition state.';
COMMENT ON COLUMN log_data.longest_no_fix_ms IS
'Longest contiguous no-fix interval observed so far in the run, in milliseconds.';
COMMENT ON COLUMN log_data.sat_talker IS
'Talker or source prefix associated with the satellite row, such as GP, GA, GL, GB, or GN.';
COMMENT ON COLUMN log_data.sat_constellation IS
'Constellation name for the satellite row, such as GPS, Galileo, GLONASS, BeiDou, NavIC, QZSS, or SBAS.';
COMMENT ON COLUMN log_data.sat_prn IS
'PRN or SVID number identifying the satellite within its constellation.';
COMMENT ON COLUMN log_data.sat_elevation_deg IS
'Satellite elevation angle above the horizon in degrees.';
COMMENT ON COLUMN log_data.sat_azimuth_deg IS
'Satellite azimuth in degrees clockwise from true north, according to receiver output.';
COMMENT ON COLUMN log_data.sat_snr IS
'Signal-to-noise style quality measure for this satellite row. Depending on firmware, this may be SNR or CN0-like output.';
COMMENT ON COLUMN log_data.sat_used_in_solution IS
'Boolean indicating whether this specific satellite was used in the navigation solution.';
COMMENT ON COLUMN log_data.raw_csv_line IS
'Original CSV line preserved verbatim for audit and recovery purposes.';
CREATE INDEX IF NOT EXISTS log_data_log_id_idx
ON log_data(log_id);
CREATE INDEX IF NOT EXISTS log_data_run_id_idx
ON log_data(run_id);
CREATE INDEX IF NOT EXISTS log_data_timestamp_idx
ON log_data(timestamp_utc);
CREATE INDEX IF NOT EXISTS log_data_record_type_idx
ON log_data(record_type);
CREATE INDEX IF NOT EXISTS log_data_board_run_seq_idx
ON log_data(board_id, run_id, sample_seq, record_type);
CREATE INDEX IF NOT EXISTS log_data_satellite_lookup_idx
ON log_data(sat_constellation, sat_prn, timestamp_utc)
WHERE record_type = 'satellite';
COMMIT;

View file

@ -0,0 +1,757 @@
// 20260406 ChatGPT
// Exercise 18_GPS_Field_QA
#include <Arduino.h>
#include <ctype.h>
#include <SPI.h>
#include <SD.h>
#include <strings.h>
#include <Wire.h>
#include <WiFi.h>
#include <WebServer.h>
#include "ClockDiscipline.h"
#include "Config.h"
#include "DisplayManager.h"
#include "GnssManager.h"
#include "RunStats.h"
#include "StartupSdManager.h"
#include "StorageManager.h"
#include "tbeam_supreme_adapter.h"
using namespace field_qa;
namespace {
XPowersLibInterface* g_pmu = nullptr;
DisplayManager g_display;
GnssManager g_gnss;
ClockDiscipline g_clock;
StorageManager g_storage;
RunStats g_stats;
StartupSdManager g_sd(Serial);
WebServer g_server(80);
char g_runId[48] = {0};
char g_bootTimestampUtc[32] = {0};
char g_serialLine[160] = {0};
char g_apSsid[32] = {0};
size_t g_serialLineLen = 0;
bool g_clockDisciplined = false;
bool g_loggingEnabled = false;
bool g_periodicSerialEnabled = false;
bool g_storageReady = false;
bool g_storageMounted = false;
bool g_webReady = false;
size_t g_logFileCount = 0;
uint32_t g_sampleSeq = 0;
uint32_t g_runStartMs = 0;
bool g_buttonPrevPressed = false;
bool g_buttonConfirmActive = false;
bool g_buttonHoldHandled = false;
uint32_t g_buttonPressedMs = 0;
uint32_t g_buttonConfirmDeadlineMs = 0;
uint32_t g_buttonStopMessageUntilMs = 0;
uint32_t g_lastSampleMs = 0;
uint32_t g_lastFlushMs = 0;
uint32_t g_lastDisplayMs = 0;
uint32_t g_lastStatusMs = 0;
uint32_t g_lastDisciplineAttemptMs = 0;
volatile uint32_t g_ppsEdgeCount = 0;
static constexpr uint32_t kButtonHoldPromptMs = 1500;
static constexpr uint32_t kButtonConfirmWindowMs = 3000;
static constexpr uint32_t kButtonStopMessageMs = 4000;
void IRAM_ATTR onPpsEdge() {
++g_ppsEdgeCount;
}
String htmlEscape(const String& in) {
String out;
out.reserve(in.length() + 16);
for (size_t i = 0; i < in.length(); ++i) {
const char c = in[i];
if (c == '&') out += "&amp;";
else if (c == '<') out += "&lt;";
else if (c == '>') out += "&gt;";
else if (c == '"') out += "&quot;";
else out += c;
}
return out;
}
String urlEncode(const String& in) {
String out;
char hex[4];
for (size_t i = 0; i < in.length(); ++i) {
const unsigned char c = (unsigned char)in[i];
if (isalnum(c) || c == '-' || c == '_' || c == '.' || c == '/' || c == '~') {
out += (char)c;
} else {
snprintf(hex, sizeof(hex), "%%%02X", c);
out += hex;
}
}
return out;
}
bool waitForNextPps(void*, uint32_t timeoutMs) {
const uint32_t startEdges = g_ppsEdgeCount;
const uint32_t startMs = millis();
while ((uint32_t)(millis() - startMs) < timeoutMs) {
g_gnss.poll();
g_sd.update();
if (g_ppsEdgeCount != startEdges) {
return true;
}
delay(2);
}
return false;
}
void setRunIdentityFromClock(const ClockDateTime& dt) {
ClockDiscipline::formatIsoUtc(dt, g_bootTimestampUtc, sizeof(g_bootTimestampUtc));
ClockDiscipline::makeRunId(dt, kBoardId, g_runId, sizeof(g_runId));
}
void printProvenance() {
Serial.printf("exercise=%s\n", kExerciseName);
Serial.printf("version=%s\n", kFirmwareVersion);
Serial.printf("board_id=%s\n", kBoardId);
Serial.printf("gnss_chip=%s\n", kGnssChip);
Serial.printf("detected_chip=%s\n", g_gnss.detectedChipName());
Serial.printf("storage=%s\n", kStorageName);
Serial.printf("sample_period_ms=%lu\n", (unsigned long)kSamplePeriodMs);
Serial.printf("log_period_ms=%lu\n", (unsigned long)kLogFlushPeriodMs);
Serial.printf("run_id=%s\n", g_runId[0] ? g_runId : "PENDING_CLOCK");
Serial.printf("clock_disciplined=%s\n", g_clockDisciplined ? "yes" : "no");
Serial.printf("web_ssid=%s\n", g_apSsid);
Serial.printf("web_url=http://192.168.%u.1/\n", (unsigned)kLogApIpOctet);
}
void printSummary() {
Serial.println("summary:");
Serial.printf("build=%s\n", kFirmwareVersion);
Serial.printf("run_id=%s\n", g_runId[0] ? g_runId : "PENDING_CLOCK");
Serial.printf("clock_disciplined=%s\n", g_clockDisciplined ? "yes" : "no");
Serial.printf("boot_timestamp_utc=%s\n", g_bootTimestampUtc[0] ? g_bootTimestampUtc : "UNKNOWN");
Serial.printf("elapsed_ms=%lu\n", (unsigned long)g_stats.elapsedMs(millis()));
Serial.printf("ttff_ms=%lu\n", (unsigned long)g_stats.ttffMs());
Serial.printf("longest_no_fix_ms=%lu\n", (unsigned long)g_stats.longestNoFixMs());
Serial.printf("storage_ready=%s\n", g_storageReady ? "yes" : "no");
Serial.printf("storage_mounted=%s\n", g_storageMounted ? "yes" : "no");
Serial.printf("storage_error=%s\n", g_storage.lastError());
Serial.printf("storage_log_dir=%s\n", kLogDir);
Serial.printf("log_file=%s\n", g_storage.currentPath());
Serial.printf("storage_file_open=%s\n", g_storage.fileOpen() ? "yes" : "no");
Serial.printf("storage_total_bytes=%u\n", g_storageMounted ? (unsigned)SD.totalBytes() : 0U);
Serial.printf("storage_used_bytes=%u\n", g_storageMounted ? (unsigned)SD.usedBytes() : 0U);
Serial.printf("storage_buffered_bytes=%u\n", (unsigned)g_storage.bufferedBytes());
Serial.printf("storage_log_count=%u\n", (unsigned)g_logFileCount);
Serial.printf("web_ready=%s\n", g_webReady ? "yes" : "no");
Serial.printf("web_url=http://192.168.%u.1/\n", (unsigned)kLogApIpOctet);
}
void printStatusLine(const GnssSample& sample) {
char ts[24];
if (sample.validTime) {
snprintf(ts,
sizeof(ts),
"%04u%02u%02u_%02u%02u%02uZ",
(unsigned)sample.year,
(unsigned)sample.month,
(unsigned)sample.day,
(unsigned)sample.hour,
(unsigned)sample.minute,
(unsigned)sample.second);
} else {
strlcpy(ts, "NO_UTC", sizeof(ts));
}
Serial.printf("%s board=%s fix=%s used=%d view=%d hdop=%s lat=%s lon=%s alt=%s q=%s clock=%s log=%s\n",
ts,
kBoardId,
fixTypeToString(sample.fixType),
sample.satsUsed < 0 ? 0 : sample.satsUsed,
sample.satsInView < 0 ? 0 : sample.satsInView,
sample.validHdop ? String(sample.hdop, 1).c_str() : "",
sample.validLocation ? String(sample.latitude, 5).c_str() : "",
sample.validLocation ? String(sample.longitude, 5).c_str() : "",
sample.validAltitude ? String(sample.altitudeM, 1).c_str() : "",
qualityClassForSample(sample),
g_clockDisciplined ? "disciplined" : "waiting",
g_loggingEnabled ? "on" : "off");
}
bool ensureStorageReady() {
if (!g_clockDisciplined || !g_storageMounted || g_storageReady || g_runId[0] == '\0') {
return g_storageReady;
}
g_logFileCount = g_storage.logFileCount();
if (g_logFileCount > kMaxLogFilesBeforePause) {
Serial.printf("INFO: auto logging paused, log count %u exceeds limit %u\n",
(unsigned)g_logFileCount,
(unsigned)kMaxLogFilesBeforePause);
return false;
}
g_storageReady = g_storage.startLog(g_runId, g_bootTimestampUtc);
if (!g_storageReady) {
Serial.printf("ERROR: log start failed: %s\n", g_storage.lastError());
return false;
}
g_sampleSeq = 0;
g_runStartMs = millis();
g_loggingEnabled = true;
g_logFileCount = g_storage.logFileCount();
Serial.printf("logging started: %s\n", g_storage.currentPath());
return true;
}
void stopLoggingCleanly(const char* reason) {
if (!g_loggingEnabled && !g_storageReady) {
return;
}
g_storage.flush();
g_storage.close();
g_storageReady = false;
g_loggingEnabled = false;
if (reason && reason[0] != '\0') {
Serial.printf("logging stopped: %s\n", reason);
} else {
Serial.println("logging stopped");
}
g_buttonStopMessageUntilMs = millis() + kButtonStopMessageMs;
}
bool rescanSdCard() {
g_storage.flush();
g_storage.close();
g_storageReady = false;
g_loggingEnabled = false;
const bool mounted = g_sd.forceRemount();
g_storageMounted = g_sd.isMounted();
if (mounted) {
g_sd.printCardInfo();
(void)ensureStorageReady();
}
return mounted;
}
void pollStopButton() {
const uint32_t now = millis();
const bool pressed = (digitalRead(BUTTON_PIN) == LOW);
if (g_buttonConfirmActive && (int32_t)(now - g_buttonConfirmDeadlineMs) >= 0) {
g_buttonConfirmActive = false;
}
if (pressed && !g_buttonPrevPressed) {
g_buttonPressedMs = now;
g_buttonHoldHandled = false;
if (g_buttonConfirmActive && g_loggingEnabled) {
stopLoggingCleanly("button confirm");
g_buttonConfirmActive = false;
}
} else if (pressed && !g_buttonHoldHandled && !g_buttonConfirmActive && g_loggingEnabled &&
(uint32_t)(now - g_buttonPressedMs) >= kButtonHoldPromptMs) {
g_buttonHoldHandled = true;
g_buttonConfirmActive = true;
g_buttonConfirmDeadlineMs = now + kButtonConfirmWindowMs;
g_display.showBoot("Stop recording?", "Press again in 3s");
}
if (!pressed && g_buttonPrevPressed) {
g_buttonHoldHandled = false;
}
g_buttonPrevPressed = pressed;
}
void handleSdStateTransitions() {
g_sd.update();
if (g_sd.consumeMountedEvent()) {
g_storageMounted = true;
Serial.println("SD mounted");
g_sd.printCardInfo();
(void)ensureStorageReady();
}
if (g_sd.consumeRemovedEvent()) {
Serial.println("SD removed");
g_storageMounted = false;
g_storage.close();
g_storageReady = false;
g_loggingEnabled = false;
}
g_storageMounted = g_sd.isMounted();
}
void attemptClockDiscipline(const GnssSample& sample) {
if (g_clockDisciplined || !sample.validTime) {
return;
}
if ((uint32_t)(millis() - g_lastDisciplineAttemptMs) < kClockDisciplineRetryMs) {
return;
}
g_lastDisciplineAttemptMs = millis();
ClockDateTime disciplinedUtc{};
bool hadPriorRtc = false;
int64_t driftSeconds = 0;
if (!g_clock.disciplineFromGnss(sample,
waitForNextPps,
nullptr,
disciplinedUtc,
hadPriorRtc,
driftSeconds)) {
Serial.println("clock discipline pending: waiting for fresh GPS time and PPS");
return;
}
setRunIdentityFromClock(disciplinedUtc);
g_clockDisciplined = true;
Serial.printf("RTC disciplined to GPS: %s", g_bootTimestampUtc);
if (hadPriorRtc) {
Serial.printf(" drift=%+llds", (long long)driftSeconds);
}
Serial.println();
g_display.showBoot("Clock disciplined", g_runId);
(void)ensureStorageReady();
}
void sampleAndMaybeLog() {
GnssSample sample = g_gnss.makeSample();
g_stats.updateFromSample(sample, millis());
sample.ttffMs = g_stats.ttffMs();
sample.longestNoFixMs = g_stats.longestNoFixMs();
attemptClockDiscipline(sample);
if (g_loggingEnabled && g_storageReady) {
const uint32_t sampleSeq = ++g_sampleSeq;
const uint32_t msSinceRunStart = millis() - g_runStartMs;
SatelliteInfo sats[kMaxSatellites];
const size_t satCount = g_gnss.copySatellites(sats, kMaxSatellites);
g_storage.appendSampleCsv(sample, sampleSeq, msSinceRunStart, g_runId, g_bootTimestampUtc);
g_storage.appendSatelliteCsv(sample, sampleSeq, msSinceRunStart, sats, satCount, g_runId, g_bootTimestampUtc);
}
if (g_periodicSerialEnabled && (uint32_t)(millis() - g_lastStatusMs) >= kStatusPeriodMs) {
g_lastStatusMs = millis();
printStatusLine(sample);
}
if ((uint32_t)(millis() - g_lastDisplayMs) >= kDisplayPeriodMs) {
g_lastDisplayMs = millis();
if (g_clockDisciplined) {
if (g_buttonConfirmActive) {
g_display.showBoot("Stop recording?", "Press again in 3s");
} else if ((uint32_t)(millis() - g_buttonStopMessageUntilMs) < kButtonStopMessageMs) {
g_display.showBoot("Halted", "Safe to power off");
} else {
g_display.showSample(sample, g_stats, g_loggingEnabled);
}
} else {
g_display.showBoot("Waiting for GPS UTC", sample.validTime ? "Awaiting PPS" : "No valid time yet");
}
}
}
void buildFileTreeHtml(String& html, const char* path) {
File dir = SD.open(path, FILE_READ);
if (!dir || !dir.isDirectory()) {
dir.close();
html += "<li>directory unavailable</li>";
return;
}
File entry = dir.openNextFile();
while (entry) {
const String name = entry.name();
String leaf = name;
const int slash = leaf.lastIndexOf('/');
if (slash >= 0) {
leaf.remove(0, slash + 1);
}
if (leaf.startsWith(".")) {
entry.close();
entry = dir.openNextFile();
continue;
}
if (entry.isDirectory()) {
String parent = path ? String(path) : String("/");
if (parent.isEmpty()) {
parent = "/";
}
if (!parent.endsWith("/")) {
parent += "/";
}
const String childPath = parent + leaf;
html += "<li><strong>";
html += htmlEscape(leaf);
html += "/</strong><ul>";
entry.close();
buildFileTreeHtml(html, childPath.c_str());
html += "</ul></li>";
} else {
String parent = path ? String(path) : String("/");
if (parent.isEmpty()) {
parent = "/";
}
if (!parent.endsWith("/")) {
parent += "/";
}
const String childPath = parent + leaf;
html += "<li>";
html += htmlEscape(leaf);
html += " (";
html += String((unsigned)entry.size());
html += " bytes) ";
html += "<a href='/download?path=";
html += urlEncode(childPath);
html += "'>download</a> ";
html += "<a href='/cmd?erase=";
html += urlEncode(childPath);
html += "'>erase</a></li>";
entry.close();
}
entry = dir.openNextFile();
}
dir.close();
}
bool normalizeWebPath(const String& input, String& out) {
return g_storage.normalizePath(input.c_str(), out);
}
void handleWebIndex() {
g_storage.flush();
String html;
html.reserve(8192);
html += "<!doctype html><html><head><meta charset='utf-8'><title>GPSQA ";
html += kBoardId;
html += "</title></head><body>";
html += "<h1>GPSQA ";
html += kBoardId;
html += "</h1><p>";
html += "Clock disciplined: ";
html += g_clockDisciplined ? "yes" : "no";
html += "<br>Run ID: ";
html += htmlEscape(g_runId[0] ? String(g_runId) : String("PENDING_CLOCK"));
html += "<br>Boot UTC: ";
html += htmlEscape(g_bootTimestampUtc[0] ? String(g_bootTimestampUtc) : String("UNKNOWN"));
html += "<br>Storage mounted: ";
html += g_storageMounted ? "yes" : "no";
html += "<br>Storage ready: ";
html += g_storageReady ? "yes" : "no";
html += "<br>Storage error: ";
html += htmlEscape(String(g_storage.lastError()));
html += "<br>Current log: ";
html += htmlEscape(String(g_storage.currentPath()));
html += "</p>";
html += "<p><a href='/cmd?status=1'>status</a> ";
html += "<a href='/cmd?flush=1'>flush</a> ";
html += "<a href='/cmd?start=1'>start</a> ";
html += "<a href='/cmd?stop=1'>stop</a> ";
html += "<a href='/cmd?sd_rescan=1'>sd_rescan</a> ";
html += "<a href='/cmd?erase_logs=1'>erase_logs</a></p>";
html += "<h2>SD Tree</h2><ul>";
if (!g_storageMounted) {
html += "<li>SD not mounted</li>";
} else {
buildFileTreeHtml(html, "/");
}
html += "</ul><p>Web commands also accept query forms like ";
html += "<code>/cmd?erase=/logs/20260406_093912_CY.csv</code></p>";
html += "</body></html>";
g_server.send(200, "text/html; charset=utf-8", html);
}
void handleWebDownload() {
g_storage.flush();
String pathArg = g_server.hasArg("path") ? g_server.arg("path") : g_server.arg("name");
String fullPath;
if (!normalizeWebPath(pathArg, fullPath)) {
g_server.send(400, "text/plain", "invalid path");
return;
}
File file = SD.open(fullPath.c_str(), FILE_READ);
if (!file) {
g_server.send(404, "text/plain", "not found");
return;
}
String downloadName = file.name();
const int slash = downloadName.lastIndexOf('/');
if (slash >= 0) {
downloadName.remove(0, slash + 1);
}
g_server.sendHeader("Content-Disposition", String("attachment; filename=\"") + downloadName + "\"");
g_server.setContentLength(file.size());
g_server.send(200, "application/octet-stream", "");
WiFiClient client = g_server.client();
uint8_t buffer[512];
while (file.available()) {
const size_t readBytes = file.read(buffer, sizeof(buffer));
if (readBytes == 0) {
break;
}
client.write(buffer, readBytes);
}
file.close();
}
void handleWebCommand() {
String response;
if (g_server.hasArg("erase")) {
g_storage.flush();
const String path = g_server.arg("erase");
if (g_storage.eraseFile(path.c_str())) {
g_storageReady = g_storage.ready();
if (!g_storageReady) {
g_loggingEnabled = false;
}
g_logFileCount = g_storage.logFileCount();
response = String("erased ") + path;
} else {
response = String("erase failed: ") + g_storage.lastError();
}
} else if (g_server.hasArg("erase_logs")) {
g_storage.flush();
g_storage.eraseLogs(Serial);
g_storageReady = g_storage.ready();
if (!g_storageReady) {
g_loggingEnabled = false;
}
g_logFileCount = g_storage.logFileCount();
response = "logs erased";
} else if (g_server.hasArg("flush")) {
g_storage.flush();
response = "buffer flushed";
} else if (g_server.hasArg("stop")) {
stopLoggingCleanly("web stop");
response = "logging stopped";
} else if (g_server.hasArg("sd_rescan")) {
response = rescanSdCard() ? "sd mounted" : "sd rescan failed";
} else if (g_server.hasArg("start")) {
if (!g_clockDisciplined) {
response = "clock not disciplined yet";
} else if (!g_storageMounted) {
response = "sd not mounted";
} else {
g_storageReady = false;
response = ensureStorageReady() ? String("logging started: ") + g_storage.currentPath()
: String("start failed: ") + g_storage.lastError();
}
} else if (g_server.hasArg("status")) {
response.reserve(256);
response += "clock_disciplined=";
response += g_clockDisciplined ? "yes" : "no";
response += "\nrun_id=";
response += g_runId[0] ? g_runId : "PENDING_CLOCK";
response += "\nlog_file=";
response += g_storage.currentPath();
response += "\nstorage_mounted=";
response += g_storageMounted ? "yes" : "no";
response += "\nstorage_ready=";
response += g_storageReady ? "yes" : "no";
response += "\nsd_state=";
response += g_storageMounted ? "mounted" : "absent";
} else {
response = "commands: status flush start stop sd_rescan erase=<path> erase_logs=1";
}
g_server.send(200, "text/plain; charset=utf-8", response);
}
void startWebServer() {
snprintf(g_apSsid, sizeof(g_apSsid), "%s%s", kLogApPrefix, kBoardId);
WiFi.mode(WIFI_AP);
IPAddress ip(192, 168, kLogApIpOctet, 1);
IPAddress gw(192, 168, kLogApIpOctet, 1);
IPAddress nm(255, 255, 255, 0);
WiFi.softAPConfig(ip, gw, nm);
if (strlen(kLogApPassword) > 0) {
WiFi.softAP(g_apSsid, kLogApPassword);
} else {
WiFi.softAP(g_apSsid, nullptr);
}
g_server.on("/", HTTP_GET, handleWebIndex);
g_server.on("/download", HTTP_GET, handleWebDownload);
g_server.on("/cmd", HTTP_GET, handleWebCommand);
g_server.begin();
g_webReady = true;
}
void handleCommand(const char* line) {
if (!line || line[0] == '\0') {
return;
}
Serial.printf("-->%s\n", line);
if (strcasecmp(line, "status") == 0) {
GnssSample sample = g_gnss.makeSample();
sample.longestNoFixMs = g_stats.longestNoFixMs();
sample.ttffMs = g_stats.ttffMs();
printStatusLine(sample);
} else if (strcasecmp(line, "summary") == 0) {
printSummary();
} else if (strcasecmp(line, "verbose") == 0) {
g_periodicSerialEnabled = true;
Serial.println("periodic status enabled");
} else if (strcasecmp(line, "quiet") == 0) {
g_periodicSerialEnabled = false;
Serial.println("periodic status disabled");
} else if (strcasecmp(line, "start") == 0) {
if (!g_clockDisciplined) {
Serial.println("clock not disciplined yet");
} else if (!g_storageMounted) {
Serial.println("sd not mounted");
} else {
g_storageReady = false;
if (ensureStorageReady()) {
Serial.println("logging started");
} else {
Serial.printf("logging start failed: %s\n", g_storage.lastError());
}
}
} else if (strcasecmp(line, "stop") == 0) {
stopLoggingCleanly("serial stop");
} else if (strcasecmp(line, "sd_rescan") == 0) {
Serial.println(rescanSdCard() ? "sd mounted" : "sd rescan failed");
} else if (strcasecmp(line, "flush") == 0) {
g_storage.flush();
Serial.println("log buffer flushed");
} else if (strcasecmp(line, "ls") == 0) {
g_storage.listFiles(Serial);
} else if (strncasecmp(line, "cat ", 4) == 0) {
g_storage.catFile(Serial, line + 4);
} else if (strncasecmp(line, "erase ", 6) == 0) {
if (g_storage.eraseFile(line + 6)) {
g_storageReady = g_storage.ready();
if (!g_storageReady) {
g_loggingEnabled = false;
}
g_logFileCount = g_storage.logFileCount();
Serial.println("file erased");
} else {
Serial.printf("erase failed: %s\n", g_storage.lastError());
}
} else if (strcasecmp(line, "erase_logs") == 0) {
g_storage.eraseLogs(Serial);
g_storageReady = g_storage.ready();
if (!g_storageReady) {
g_loggingEnabled = false;
}
g_logFileCount = g_storage.logFileCount();
} else if (strcasecmp(line, "discipline") == 0) {
g_clockDisciplined = false;
g_lastDisciplineAttemptMs = 0;
Serial.println("clock discipline requested");
} else {
Serial.println("commands: status quiet verbose flush start stop sd_rescan summary ls cat <path> erase <path> erase_logs discipline");
}
}
void pollSerialConsole() {
while (Serial.available() > 0) {
const int c = Serial.read();
if (c < 0) {
continue;
}
if (c == '\r' || c == '\n') {
if (g_serialLineLen > 0) {
g_serialLine[g_serialLineLen] = '\0';
handleCommand(g_serialLine);
g_serialLineLen = 0;
}
continue;
}
if (g_serialLineLen + 1 < sizeof(g_serialLine)) {
g_serialLine[g_serialLineLen++] = (char)c;
} else {
g_serialLineLen = 0;
}
}
}
} // namespace
void setup() {
Serial.begin(115200);
delay(kSerialDelayMs);
Serial.println();
Serial.println("==================================================");
Serial.println("Exercise 18: GPS Field QA");
Serial.println("==================================================");
if (!tbeam_supreme::initPmuForPeripherals(g_pmu, &Serial)) {
Serial.println("WARNING: PMU init failed");
}
g_display.begin();
pinMode(BUTTON_PIN, INPUT_PULLUP);
g_display.showBoot("Booting...", kBoardId);
g_stats.begin(millis());
g_gnss.begin();
(void)g_gnss.probeAtStartup(Serial);
startWebServer();
SdWatcherConfig sdCfg;
if (!g_sd.begin(sdCfg)) {
Serial.println("WARNING: SD watcher init failed");
}
g_storageMounted = g_sd.isMounted();
if (g_storageMounted) {
g_sd.printCardInfo();
}
#ifdef GPS_1PPS_PIN
attachInterrupt(digitalPinToInterrupt(GPS_1PPS_PIN), onPpsEdge, RISING);
#endif
ClockDateTime rtcNow{};
int64_t rtcEpoch = 0;
if (g_clock.readValidRtc(rtcNow, &rtcEpoch)) {
char rtcIso[32];
ClockDiscipline::formatIsoUtc(rtcNow, rtcIso, sizeof(rtcIso));
Serial.printf("RTC present at boot: %s\n", rtcIso);
} else {
Serial.println("RTC invalid at boot");
}
printProvenance();
g_display.showBoot("Waiting for GPS UTC", "No log before RTC set");
g_lastSampleMs = millis();
g_lastFlushMs = millis();
}
void loop() {
pollSerialConsole();
pollStopButton();
g_gnss.poll();
handleSdStateTransitions();
g_server.handleClient();
const uint32_t now = millis();
if ((uint32_t)(now - g_lastSampleMs) >= kSamplePeriodMs) {
g_lastSampleMs = now;
sampleAndMaybeLog();
}
if (g_storageReady && (uint32_t)(now - g_lastFlushMs) >= kLogFlushPeriodMs) {
g_lastFlushMs = now;
g_storage.flush();
}
}

View file

@ -92,3 +92,71 @@ shared board pin headers in one place:
You can read and write to SD cards that are FAT formatted. (Can they be Linux formatted?)
## Real Time Clock ("RTC")
## Microphone
# Creating Automatic Recognition by udev
## Find the unique ID.
This assumes that your device is being assigned to ACM0 when you connect it with your workstation.
jlpoole@jp ~ $ udevadm info -a -n /dev/ttyACM0 | nl| grep serial
67 ATTRS{product}=="USB JTAG/serial debug unit"
72 ATTRS{serial}=="48:CA:43:5A:8C:74"
282 ATTRS{serial}=="0000:00:1a.7"
jlpoole@jp ~ $
The 6 token value delimited by colons is the unique ID.
## Adding a UDEV rule
Create a udev rule modeled after the ones below:
/etc/udev/rules.d/99-ttyt-tbeam.rules
Sample content for devices that will be named AMY-GUY
# 99-ttyt-tbeam.rules
# LilyGO T-Beam SUPREME (ESP32-S3 USB JTAG/serial debug unit)
# Create stable symlinks: /dev/ttytAMY, /dev/ttytBOB, ...
SUBSYSTEM=="tty", ATTRS{idVendor}=="303a", ATTRS{idProduct}=="1001", ATTRS{serial}=="48:CA:43:5B:BF:68", MODE:="0660", GROUP:="dialout",SYMLINK+="ttytAMY"
SUBSYSTEM=="tty", ATTRS{idVendor}=="303a", ATTRS{idProduct}=="1001", ATTRS{serial}=="48:CA:43:5A:93:DC", MODE:="0660", GROUP:="dialout",SYMLINK+="ttytBOB"
SUBSYSTEM=="tty", ATTRS{idVendor}=="303a", ATTRS{idProduct}=="1001", ATTRS{serial}=="48:CA:43:5A:91:44", MODE:="0660", GROUP:="dialout",SYMLINK+="ttytCY"
SUBSYSTEM=="tty", ATTRS{idVendor}=="303a", ATTRS{idProduct}=="1001", ATTRS{serial}=="48:CA:43:5A:93:A0", MODE:="0660", GROUP:="dialout",SYMLINK+="ttytDAN"
SUBSYSTEM=="tty", ATTRS{idVendor}=="303a", ATTRS{idProduct}=="1001", ATTRS{serial}=="48:CA:43:5A:90:D0", MODE:="0660", GROUP:="dialout",SYMLINK+="ttytED"
Then:
sudo udevadm control --reload-rules
sudo udevadm trigger --subsystem-match=tty
Sanity check command when a device is plugged in:
udevadm info -a -n /dev/ttyACM0 | less
## Example Walk-through
Here's a complete walk-thru
jlpoole@jp ~ $ date; udevadm info -a -n /dev/ttyACM0 | nl| grep serial
Fri Apr 3 10:54:25 PDT 2026
67 ATTRS{product}=="USB JTAG/serial debug unit"
72 ATTRS{serial}=="48:CA:43:5A:40:E0"
282 ATTRS{serial}=="0000:00:1a.7"
jlpoole@jp ~ $ # GUY=48:CA:43:5A:40:E0
jlpoole@jp ~ $ sudo nano /etc/udev/rules.d/99-ttyt-tbeam.rules
jlpoole@jp ~ $ sudo udevadm control --reload-rules
jlpoole@jp ~ $ sudo udevadm trigger --subsystem-match=tty
jlpoole@jp ~ $ ls /dev/ttyt*
/dev/ttytGUY
jlpoole@jp ~ $
Xtras:
To customize your system so when the unit is attached, it will have the same name, e.g. /dev/ttytBOB:
You'll need the id, use this when the unit is plugged in:
pio device list |grep -A3