Stabilized logging to SD Card, disciplined time, and web fetch & erase
This commit is contained in:
parent
e3f6527274
commit
e28ebe5b17
15 changed files with 1536 additions and 510 deletions
18
docs/gps.md
18
docs/gps.md
|
|
@ -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!
|
||||||
|
|
@ -132,3 +132,10 @@ You are saying:
|
||||||
> “Use PlatformIO to build this firmware for the specified environment and flash it to the target device.”
|
> “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
|
||||||
|
|
@ -9,3 +9,12 @@ 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
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -2,11 +2,11 @@
|
||||||
|
|
||||||
Survey/reconnaissance firmware for LilyGO T-Beam SUPREME.
|
Survey/reconnaissance firmware for LilyGO T-Beam SUPREME.
|
||||||
|
|
||||||
This exercise measures GNSS visibility and solution quality, logs results to internal flash using CSV, and provides a minimal serial interface for retrieving the logs in the field.
|
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:
|
Current storage choice:
|
||||||
|
|
||||||
- `SPIFFS`
|
- `SD`
|
||||||
|
|
||||||
Current environments:
|
Current environments:
|
||||||
|
|
||||||
|
|
@ -18,13 +18,21 @@ Primary serial commands:
|
||||||
- `status`
|
- `status`
|
||||||
- `summary`
|
- `summary`
|
||||||
- `ls`
|
- `ls`
|
||||||
- `cat <filename>`
|
- `cat <path>`
|
||||||
|
- `erase <path>`
|
||||||
- `stop`
|
- `stop`
|
||||||
|
- `start`
|
||||||
|
- `flush`
|
||||||
|
- `discipline`
|
||||||
- `erase_logs`
|
- `erase_logs`
|
||||||
|
|
||||||
Notes:
|
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.
|
- Samples are aggregated once per second.
|
||||||
- Records are flushed to flash every 10 seconds.
|
- 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.
|
- 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.
|
- The implementation uses common NMEA parsing so it can normalize L76K and MAX-M10S output without adding a new GNSS dependency.
|
||||||
|
|
|
||||||
241
exercises/18_GPS_Field_QA/lib/field_qa/ClockDiscipline.cpp
Normal file
241
exercises/18_GPS_Field_QA/lib/field_qa/ClockDiscipline.cpp
Normal 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
|
||||||
53
exercises/18_GPS_Field_QA/lib/field_qa/ClockDiscipline.h
Normal file
53
exercises/18_GPS_Field_QA/lib/field_qa/ClockDiscipline.h
Normal 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
|
||||||
|
|
@ -51,8 +51,8 @@ static constexpr const char* kExerciseName = "18_GPS_Field_QA";
|
||||||
static constexpr const char* kFirmwareVersion = FIELD_QA_STR(FW_BUILD_UTC);
|
static constexpr const char* kFirmwareVersion = FIELD_QA_STR(FW_BUILD_UTC);
|
||||||
static constexpr const char* kBoardId = BOARD_ID;
|
static constexpr const char* kBoardId = BOARD_ID;
|
||||||
static constexpr const char* kGnssChip = GNSS_CHIP_NAME;
|
static constexpr const char* kGnssChip = GNSS_CHIP_NAME;
|
||||||
static constexpr const char* kStorageName = "SPIFFS";
|
static constexpr const char* kStorageName = "SD";
|
||||||
static constexpr const char* kLogDir = "/";
|
static constexpr const char* kLogDir = "/logs";
|
||||||
static constexpr const char* kLogApPrefix = "GPSQA-";
|
static constexpr const char* kLogApPrefix = "GPSQA-";
|
||||||
static constexpr const char* kLogApPassword = "";
|
static constexpr const char* kLogApPassword = "";
|
||||||
static constexpr uint8_t kLogApIpOctet = 23;
|
static constexpr uint8_t kLogApIpOctet = 23;
|
||||||
|
|
@ -64,7 +64,6 @@ static constexpr uint32_t kStatusPeriodMs = 1000;
|
||||||
static constexpr uint32_t kProbeWindowL76kMs = 20000;
|
static constexpr uint32_t kProbeWindowL76kMs = 20000;
|
||||||
static constexpr uint32_t kProbeWindowUbloxMs = 45000;
|
static constexpr uint32_t kProbeWindowUbloxMs = 45000;
|
||||||
static constexpr uint32_t kFixFreshMs = 5000;
|
static constexpr uint32_t kFixFreshMs = 5000;
|
||||||
static constexpr size_t kMaxLogFilesBeforePause = 5;
|
|
||||||
static constexpr uint8_t kPoorMinSatsUsed = 4;
|
static constexpr uint8_t kPoorMinSatsUsed = 4;
|
||||||
static constexpr uint8_t kGoodMinSatsUsed = 10;
|
static constexpr uint8_t kGoodMinSatsUsed = 10;
|
||||||
static constexpr uint8_t kExcellentMinSatsUsed = 16;
|
static constexpr uint8_t kExcellentMinSatsUsed = 16;
|
||||||
|
|
@ -72,5 +71,10 @@ static constexpr float kMarginalHdop = 3.0f;
|
||||||
static constexpr float kExcellentHdop = 1.5f;
|
static constexpr float kExcellentHdop = 1.5f;
|
||||||
static constexpr size_t kBufferedSamples = 10;
|
static constexpr size_t kBufferedSamples = 10;
|
||||||
static constexpr size_t kMaxSatellites = 64;
|
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
|
} // namespace field_qa
|
||||||
|
|
|
||||||
|
|
@ -58,36 +58,12 @@ static const char* constellationForTalker(const char* talker) {
|
||||||
|
|
||||||
} // namespace
|
} // namespace
|
||||||
|
|
||||||
bool StorageManager::mount() {
|
|
||||||
m_ready = false;
|
|
||||||
m_lastError = "";
|
|
||||||
m_path = "";
|
|
||||||
m_buffer = "";
|
|
||||||
if (m_file) {
|
|
||||||
m_file.close();
|
|
||||||
}
|
|
||||||
if (!SPIFFS.begin(true)) {
|
|
||||||
m_lastError = "SPIFFS.begin failed";
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
if (!ensureDir()) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool StorageManager::begin(const char* runId) {
|
|
||||||
if (!mount()) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
return startLog(runId, "");
|
|
||||||
}
|
|
||||||
|
|
||||||
bool StorageManager::startLog(const char* runId, const char* bootTimestampUtc) {
|
bool StorageManager::startLog(const char* runId, const char* bootTimestampUtc) {
|
||||||
|
close();
|
||||||
m_ready = false;
|
m_ready = false;
|
||||||
m_lastError = "";
|
m_lastError = "";
|
||||||
m_path = makeFilePath(runId);
|
m_path = makeFilePath(runId);
|
||||||
if (!openFile()) {
|
if (!ensureDir() || !openFile()) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
m_ready = true;
|
m_ready = true;
|
||||||
|
|
@ -96,8 +72,10 @@ bool StorageManager::startLog(const char* runId, const char* bootTimestampUtc) {
|
||||||
}
|
}
|
||||||
|
|
||||||
bool StorageManager::mounted() const {
|
bool StorageManager::mounted() const {
|
||||||
File root = SPIFFS.open("/");
|
File root = SD.open("/", FILE_READ);
|
||||||
return root && root.isDirectory();
|
const bool ok = root && root.isDirectory();
|
||||||
|
root.close();
|
||||||
|
return ok;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool StorageManager::ready() const {
|
bool StorageManager::ready() const {
|
||||||
|
|
@ -117,76 +95,76 @@ bool StorageManager::fileOpen() const {
|
||||||
}
|
}
|
||||||
|
|
||||||
size_t StorageManager::bufferedBytes() const {
|
size_t StorageManager::bufferedBytes() const {
|
||||||
return m_buffer.length();
|
return m_bufferLengths[0] + m_bufferLengths[1];
|
||||||
}
|
}
|
||||||
|
|
||||||
size_t StorageManager::logFileCount() const {
|
size_t StorageManager::countLogsRecursive(const char* path) const {
|
||||||
File dir = SPIFFS.open("/");
|
File dir = SD.open(path, FILE_READ);
|
||||||
if (!dir || !dir.isDirectory()) {
|
if (!dir || !dir.isDirectory()) {
|
||||||
|
dir.close();
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
size_t count = 0;
|
size_t count = 0;
|
||||||
File file = dir.openNextFile();
|
File entry = dir.openNextFile();
|
||||||
while (file) {
|
while (entry) {
|
||||||
String name = file.name();
|
String name = entry.name();
|
||||||
if (isRecognizedLogName(name)) {
|
if (entry.isDirectory()) {
|
||||||
|
count += countLogsRecursive(name.c_str());
|
||||||
|
} else if (isRecognizedLogName(name)) {
|
||||||
++count;
|
++count;
|
||||||
}
|
}
|
||||||
file = dir.openNextFile();
|
entry.close();
|
||||||
|
entry = dir.openNextFile();
|
||||||
}
|
}
|
||||||
|
dir.close();
|
||||||
return count;
|
return count;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
size_t StorageManager::logFileCount() const {
|
||||||
|
return countLogsRecursive(kLogDir);
|
||||||
|
}
|
||||||
|
|
||||||
bool StorageManager::ensureDir() {
|
bool StorageManager::ensureDir() {
|
||||||
if (strcmp(kLogDir, "/") == 0) {
|
String full(kLogDir);
|
||||||
return true;
|
if (!full.startsWith("/")) {
|
||||||
|
full = "/" + full;
|
||||||
}
|
}
|
||||||
if (SPIFFS.exists(kLogDir)) {
|
|
||||||
return true;
|
int start = 1;
|
||||||
}
|
while (start > 0 && start < (int)full.length()) {
|
||||||
if (!SPIFFS.mkdir(kLogDir)) {
|
const int slash = full.indexOf('/', start);
|
||||||
m_lastError = "SPIFFS.mkdir failed";
|
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;
|
return false;
|
||||||
}
|
}
|
||||||
|
if (slash < 0) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
start = slash + 1;
|
||||||
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
String StorageManager::makeFilePath(const char* runId) const {
|
String StorageManager::makeFilePath(const char* runId) const {
|
||||||
char path[96];
|
char path[96];
|
||||||
const char* rid = runId ? runId : "run";
|
const char* rid = (runId && runId[0] != '\0') ? runId : "run";
|
||||||
char shortId[32];
|
snprintf(path, sizeof(path), "%s/%s.csv", kLogDir, rid);
|
||||||
if (strlen(rid) >= 19 && rid[8] == '_' && rid[15] == '_') {
|
|
||||||
snprintf(shortId,
|
|
||||||
sizeof(shortId),
|
|
||||||
"%.6s_%.6s_%s",
|
|
||||||
rid + 2,
|
|
||||||
rid + 9,
|
|
||||||
rid + 16);
|
|
||||||
} else {
|
|
||||||
snprintf(shortId, sizeof(shortId), "%s", rid);
|
|
||||||
}
|
|
||||||
if (strcmp(kLogDir, "/") == 0) {
|
|
||||||
snprintf(path, sizeof(path), "/%s.csv", shortId);
|
|
||||||
} else {
|
|
||||||
snprintf(path, sizeof(path), "%s/%s.csv", kLogDir, shortId);
|
|
||||||
}
|
|
||||||
return String(path);
|
return String(path);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool StorageManager::openFile() {
|
bool StorageManager::openFile() {
|
||||||
m_file = SPIFFS.open(m_path, FILE_WRITE);
|
m_file = SD.open(m_path.c_str(), FILE_WRITE);
|
||||||
if (!m_file) {
|
if (!m_file) {
|
||||||
m_lastError = "SPIFFS.open write failed";
|
m_lastError = "SD.open write failed";
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void StorageManager::writeHeader(const char* runId, const char* bootTimestampUtc) {
|
void StorageManager::writeHeader(const char* runId, const char* bootTimestampUtc) {
|
||||||
if (!m_file) {
|
if (!m_file || m_file.size() > 0) {
|
||||||
return;
|
|
||||||
}
|
|
||||||
if (m_file.size() > 0) {
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
m_file.printf("# exercise: %s\n", kExerciseName);
|
m_file.printf("# exercise: %s\n", kExerciseName);
|
||||||
|
|
@ -199,27 +177,99 @@ void StorageManager::writeHeader(const char* runId, const char* bootTimestampUtc
|
||||||
m_file.printf("# run_id: %s\n", runId ? runId : "");
|
m_file.printf("# run_id: %s\n", runId ? runId : "");
|
||||||
m_file.printf("# boot_timestamp_utc: %s\n", bootTimestampUtc ? bootTimestampUtc : "");
|
m_file.printf("# boot_timestamp_utc: %s\n", bootTimestampUtc ? bootTimestampUtc : "");
|
||||||
m_file.printf("# created_by: ChatGPT/Codex handoff\n");
|
m_file.printf("# created_by: ChatGPT/Codex handoff\n");
|
||||||
m_file.print("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\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_file.flush();
|
||||||
}
|
}
|
||||||
|
|
||||||
void StorageManager::appendLine(const String& line) {
|
bool StorageManager::writePendingBuffer() {
|
||||||
m_buffer += line;
|
if (!m_file) {
|
||||||
if (!m_buffer.endsWith("\n")) {
|
return false;
|
||||||
m_buffer += "\n";
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
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;
|
||||||
}
|
}
|
||||||
|
|
||||||
void StorageManager::appendSampleTsv(const GnssSample& sample, const char* runId, const char* bootTimestampUtc) {
|
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 (!appendBytes(line.c_str(), line.length())) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (!line.endsWith("\n")) {
|
||||||
|
static const char newline = '\n';
|
||||||
|
return appendBytes(&newline, 1);
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void StorageManager::appendSampleCsv(const GnssSample& sample,
|
||||||
|
uint32_t sampleSeq,
|
||||||
|
uint32_t msSinceRunStart,
|
||||||
|
const char* runId,
|
||||||
|
const char* bootTimestampUtc) {
|
||||||
if (!m_file) {
|
if (!m_file) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (m_file.size() == 0) {
|
if (m_file.size() == 0) {
|
||||||
writeHeader(runId, bootTimestampUtc);
|
writeHeader(runId, bootTimestampUtc);
|
||||||
}
|
}
|
||||||
|
|
||||||
String line = "sample,";
|
String line = "sample,";
|
||||||
line += sampleTimestamp(sample);
|
line += sampleTimestamp(sample);
|
||||||
line += kLogFieldDelimiter;
|
line += kLogFieldDelimiter;
|
||||||
|
line += String(sampleSeq);
|
||||||
|
line += kLogFieldDelimiter;
|
||||||
|
line += String(msSinceRunStart);
|
||||||
|
line += kLogFieldDelimiter;
|
||||||
line += kBoardId;
|
line += kBoardId;
|
||||||
line += kLogFieldDelimiter;
|
line += kLogFieldDelimiter;
|
||||||
line += kGnssChip;
|
line += kGnssChip;
|
||||||
|
|
@ -286,10 +336,12 @@ void StorageManager::appendSampleTsv(const GnssSample& sample, const char* runId
|
||||||
line += kLogFieldDelimiter;
|
line += kLogFieldDelimiter;
|
||||||
line += String(sample.longestNoFixMs);
|
line += String(sample.longestNoFixMs);
|
||||||
line += ",,,,,,,";
|
line += ",,,,,,,";
|
||||||
appendLine(line);
|
(void)appendLine(line);
|
||||||
}
|
}
|
||||||
|
|
||||||
void StorageManager::appendSatelliteTsv(const GnssSample& sample,
|
void StorageManager::appendSatelliteCsv(const GnssSample& sample,
|
||||||
|
uint32_t sampleSeq,
|
||||||
|
uint32_t msSinceRunStart,
|
||||||
const SatelliteInfo* satellites,
|
const SatelliteInfo* satellites,
|
||||||
size_t satelliteCount,
|
size_t satelliteCount,
|
||||||
const char* runId,
|
const char* runId,
|
||||||
|
|
@ -309,6 +361,10 @@ void StorageManager::appendSatelliteTsv(const GnssSample& sample,
|
||||||
String line = "satellite,";
|
String line = "satellite,";
|
||||||
line += sampleTimestamp(sample);
|
line += sampleTimestamp(sample);
|
||||||
line += kLogFieldDelimiter;
|
line += kLogFieldDelimiter;
|
||||||
|
line += String(sampleSeq);
|
||||||
|
line += kLogFieldDelimiter;
|
||||||
|
line += String(msSinceRunStart);
|
||||||
|
line += kLogFieldDelimiter;
|
||||||
line += kBoardId;
|
line += kBoardId;
|
||||||
line += kLogFieldDelimiter;
|
line += kLogFieldDelimiter;
|
||||||
line += kGnssChip;
|
line += kGnssChip;
|
||||||
|
|
@ -388,17 +444,22 @@ void StorageManager::appendSatelliteTsv(const GnssSample& sample,
|
||||||
line += String(sat.snr);
|
line += String(sat.snr);
|
||||||
line += kLogFieldDelimiter;
|
line += kLogFieldDelimiter;
|
||||||
line += sat.usedInSolution ? "1" : "0";
|
line += sat.usedInSolution ? "1" : "0";
|
||||||
appendLine(line);
|
(void)appendLine(line);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void StorageManager::flush() {
|
void StorageManager::flush() {
|
||||||
if (!m_file || m_buffer.isEmpty()) {
|
if (!m_file) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (m_bufferLengths[m_activeBuffer] > 0) {
|
||||||
|
m_bufferPending[m_activeBuffer] = true;
|
||||||
|
}
|
||||||
|
if (!writePendingBuffer()) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
m_file.print(m_buffer);
|
|
||||||
m_file.flush();
|
m_file.flush();
|
||||||
m_buffer = "";
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void StorageManager::close() {
|
void StorageManager::close() {
|
||||||
|
|
@ -406,6 +467,36 @@ void StorageManager::close() {
|
||||||
if (m_file) {
|
if (m_file) {
|
||||||
m_file.close();
|
m_file.close();
|
||||||
}
|
}
|
||||||
|
m_ready = 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) {
|
void StorageManager::listFiles(Stream& out) {
|
||||||
|
|
@ -413,23 +504,14 @@ void StorageManager::listFiles(Stream& out) {
|
||||||
out.println("storage not mounted");
|
out.println("storage not mounted");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
File dir = SPIFFS.open("/");
|
File dir = SD.open(kLogDir, FILE_READ);
|
||||||
if (!dir || !dir.isDirectory()) {
|
if (!dir || !dir.isDirectory()) {
|
||||||
out.println("root directory unavailable");
|
out.println("log directory unavailable");
|
||||||
|
dir.close();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
File file = dir.openNextFile();
|
listFilesRecursive(dir, out);
|
||||||
if (!file) {
|
dir.close();
|
||||||
out.println("(no files)");
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
while (file) {
|
|
||||||
String name = file.name();
|
|
||||||
if (isRecognizedLogName(name)) {
|
|
||||||
out.printf("%s\t%u\n", file.name(), (unsigned)file.size());
|
|
||||||
}
|
|
||||||
file = dir.openNextFile();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void StorageManager::catFile(Stream& out, const char* path) {
|
void StorageManager::catFile(Stream& out, const char* path) {
|
||||||
|
|
@ -437,12 +519,12 @@ void StorageManager::catFile(Stream& out, const char* path) {
|
||||||
out.println("storage not mounted");
|
out.println("storage not mounted");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (!path || path[0] == '\0') {
|
String fullPath;
|
||||||
out.println("cat requires a filename");
|
if (!normalizePath(path, fullPath)) {
|
||||||
|
out.println("cat requires a valid filename");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
String fullPath = path[0] == '/' ? String(path) : String("/") + path;
|
File file = SD.open(fullPath.c_str(), FILE_READ);
|
||||||
File file = SPIFFS.open(fullPath, FILE_READ);
|
|
||||||
if (!file) {
|
if (!file) {
|
||||||
out.printf("unable to open %s\n", fullPath.c_str());
|
out.printf("unable to open %s\n", fullPath.c_str());
|
||||||
return;
|
return;
|
||||||
|
|
@ -453,6 +535,26 @@ void StorageManager::catFile(Stream& out, const char* path) {
|
||||||
if (file.size() > 0) {
|
if (file.size() > 0) {
|
||||||
out.println();
|
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) {
|
void StorageManager::eraseLogs(Stream& out) {
|
||||||
|
|
@ -460,22 +562,35 @@ void StorageManager::eraseLogs(Stream& out) {
|
||||||
out.println("storage not mounted");
|
out.println("storage not mounted");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
File dir = SPIFFS.open("/");
|
File dir = SD.open(kLogDir, FILE_READ);
|
||||||
if (!dir || !dir.isDirectory()) {
|
if (!dir || !dir.isDirectory()) {
|
||||||
out.println("root directory unavailable");
|
out.println("log directory unavailable");
|
||||||
|
dir.close();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
File file = dir.openNextFile();
|
eraseLogsRecursive(dir);
|
||||||
while (file) {
|
dir.close();
|
||||||
String path = file.path();
|
|
||||||
bool isLog = isRecognizedLogName(path);
|
|
||||||
file.close();
|
|
||||||
if (isLog) {
|
|
||||||
SPIFFS.remove(path);
|
|
||||||
}
|
|
||||||
file = dir.openNextFile();
|
|
||||||
}
|
|
||||||
out.println("logs erased");
|
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
|
} // namespace field_qa
|
||||||
|
|
|
||||||
|
|
@ -1,15 +1,14 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include <SPIFFS.h>
|
#include <SD.h>
|
||||||
|
#include "Config.h"
|
||||||
#include "GnssTypes.h"
|
#include "GnssTypes.h"
|
||||||
|
|
||||||
namespace field_qa {
|
namespace field_qa {
|
||||||
|
|
||||||
class StorageManager {
|
class StorageManager {
|
||||||
public:
|
public:
|
||||||
bool mount();
|
|
||||||
bool begin(const char* runId);
|
|
||||||
bool startLog(const char* runId, const char* bootTimestampUtc);
|
bool startLog(const char* runId, const char* bootTimestampUtc);
|
||||||
bool mounted() const;
|
bool mounted() const;
|
||||||
bool ready() const;
|
bool ready() const;
|
||||||
|
|
@ -18,8 +17,14 @@ class StorageManager {
|
||||||
bool fileOpen() const;
|
bool fileOpen() const;
|
||||||
size_t bufferedBytes() const;
|
size_t bufferedBytes() const;
|
||||||
size_t logFileCount() const;
|
size_t logFileCount() const;
|
||||||
void appendSampleTsv(const GnssSample& sample, const char* runId, const char* bootTimestampUtc);
|
void appendSampleCsv(const GnssSample& sample,
|
||||||
void appendSatelliteTsv(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,
|
const SatelliteInfo* satellites,
|
||||||
size_t satelliteCount,
|
size_t satelliteCount,
|
||||||
const char* runId,
|
const char* runId,
|
||||||
|
|
@ -29,19 +34,29 @@ class StorageManager {
|
||||||
void listFiles(Stream& out);
|
void listFiles(Stream& out);
|
||||||
void catFile(Stream& out, const char* path);
|
void catFile(Stream& out, const char* path);
|
||||||
void eraseLogs(Stream& out);
|
void eraseLogs(Stream& out);
|
||||||
|
bool eraseFile(const char* path);
|
||||||
|
bool normalizePath(const char* input, String& normalized) const;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
bool ensureDir();
|
bool ensureDir();
|
||||||
bool openFile();
|
bool openFile();
|
||||||
void writeHeader(const char* runId, const char* bootTimestampUtc);
|
void writeHeader(const char* runId, const char* bootTimestampUtc);
|
||||||
String makeFilePath(const char* runId) const;
|
String makeFilePath(const char* runId) const;
|
||||||
void appendLine(const String& line);
|
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_ready = false;
|
||||||
String m_path;
|
String m_path;
|
||||||
String m_lastError;
|
String m_lastError;
|
||||||
File m_file;
|
File m_file;
|
||||||
String m_buffer;
|
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
|
} // namespace field_qa
|
||||||
|
|
|
||||||
360
exercises/18_GPS_Field_QA/lib/startup_sd/StartupSdManager.cpp
Normal file
360
exercises/18_GPS_Field_QA/lib/startup_sd/StartupSdManager.cpp
Normal file
|
|
@ -0,0 +1,360 @@
|
||||||
|
#include "StartupSdManager.h"
|
||||||
|
|
||||||
|
#include <stdarg.h>
|
||||||
|
#include "driver/gpio.h"
|
||||||
|
|
||||||
|
StartupSdManager::StartupSdManager(Print& serial) : serial_(serial) {}
|
||||||
|
|
||||||
|
bool StartupSdManager::begin(const SdWatcherConfig& cfg, SdStatusCallback callback) {
|
||||||
|
cfg_ = cfg;
|
||||||
|
callback_ = callback;
|
||||||
|
|
||||||
|
forceSpiDeselected();
|
||||||
|
dumpSdPins("very-early");
|
||||||
|
|
||||||
|
if (!initPmuForSdPower()) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
cycleSdRail();
|
||||||
|
delay(cfg_.startupWarmupMs);
|
||||||
|
|
||||||
|
bool warmMounted = false;
|
||||||
|
for (uint8_t i = 0; i < 3; ++i) {
|
||||||
|
if (mountPreferred(false)) {
|
||||||
|
warmMounted = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
delay(200);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Some cards need a longer power/settle window after cold boot.
|
||||||
|
// Before declaring ABSENT, retry with extended settle and a full scan.
|
||||||
|
if (!warmMounted) {
|
||||||
|
logf("Watcher: startup preferred mount failed, retrying with extended settle");
|
||||||
|
cycleSdRail(400, 1200);
|
||||||
|
delay(cfg_.startupWarmupMs + 1500);
|
||||||
|
warmMounted = mountCardFullScan();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (warmMounted) {
|
||||||
|
setStateMounted();
|
||||||
|
} else {
|
||||||
|
setStateAbsent();
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void StartupSdManager::update() {
|
||||||
|
const uint32_t now = millis();
|
||||||
|
const uint32_t pollInterval =
|
||||||
|
(watchState_ == SdWatchState::MOUNTED) ? cfg_.pollIntervalMountedMs : cfg_.pollIntervalAbsentMs;
|
||||||
|
|
||||||
|
if ((uint32_t)(now - lastPollMs_) < pollInterval) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
lastPollMs_ = now;
|
||||||
|
|
||||||
|
if (watchState_ == SdWatchState::MOUNTED) {
|
||||||
|
if (verifyMountedCard()) {
|
||||||
|
presentVotes_ = 0;
|
||||||
|
absentVotes_ = 0;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (mountPreferred(false) && verifyMountedCard()) {
|
||||||
|
presentVotes_ = 0;
|
||||||
|
absentVotes_ = 0;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
absentVotes_++;
|
||||||
|
presentVotes_ = 0;
|
||||||
|
if (absentVotes_ >= cfg_.votesToAbsent) {
|
||||||
|
setStateAbsent();
|
||||||
|
absentVotes_ = 0;
|
||||||
|
}
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool mounted = mountPreferred(false);
|
||||||
|
if (!mounted && (uint32_t)(now - lastFullScanMs_) >= cfg_.fullScanIntervalMs) {
|
||||||
|
lastFullScanMs_ = now;
|
||||||
|
if (cfg_.recoveryRailCycleOnFullScan) {
|
||||||
|
logf("Watcher: recovery rail cycle before full scan");
|
||||||
|
cycleSdRail(cfg_.recoveryRailOffMs, cfg_.recoveryRailOnSettleMs);
|
||||||
|
delay(150);
|
||||||
|
}
|
||||||
|
logf("Watcher: preferred probe failed, running full scan");
|
||||||
|
mounted = mountCardFullScan();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (mounted) {
|
||||||
|
presentVotes_++;
|
||||||
|
absentVotes_ = 0;
|
||||||
|
if (presentVotes_ >= cfg_.votesToPresent) {
|
||||||
|
setStateMounted();
|
||||||
|
presentVotes_ = 0;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
absentVotes_++;
|
||||||
|
presentVotes_ = 0;
|
||||||
|
if (absentVotes_ >= cfg_.votesToAbsent) {
|
||||||
|
setStateAbsent();
|
||||||
|
absentVotes_ = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool StartupSdManager::consumeMountedEvent() {
|
||||||
|
bool out = mountedEventPending_;
|
||||||
|
mountedEventPending_ = false;
|
||||||
|
return out;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool StartupSdManager::consumeRemovedEvent() {
|
||||||
|
bool out = removedEventPending_;
|
||||||
|
removedEventPending_ = false;
|
||||||
|
return out;
|
||||||
|
}
|
||||||
|
|
||||||
|
void StartupSdManager::logf(const char* fmt, ...) {
|
||||||
|
char msg[196];
|
||||||
|
va_list args;
|
||||||
|
va_start(args, fmt);
|
||||||
|
vsnprintf(msg, sizeof(msg), fmt, args);
|
||||||
|
va_end(args);
|
||||||
|
serial_.printf("[%10lu][%06lu] %s\r\n",
|
||||||
|
(unsigned long)millis(),
|
||||||
|
(unsigned long)logSeq_++,
|
||||||
|
msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
void StartupSdManager::notify(SdEvent event, const char* message) {
|
||||||
|
if (callback_ != nullptr) {
|
||||||
|
callback_(event, message);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void StartupSdManager::forceSpiDeselected() {
|
||||||
|
pinMode(tbeam_supreme::sdCs(), OUTPUT);
|
||||||
|
digitalWrite(tbeam_supreme::sdCs(), HIGH);
|
||||||
|
pinMode(tbeam_supreme::imuCs(), OUTPUT);
|
||||||
|
digitalWrite(tbeam_supreme::imuCs(), HIGH);
|
||||||
|
}
|
||||||
|
|
||||||
|
void StartupSdManager::dumpSdPins(const char* tag) {
|
||||||
|
if (!cfg_.enablePinDumps) {
|
||||||
|
(void)tag;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
const gpio_num_t cs = (gpio_num_t)tbeam_supreme::sdCs();
|
||||||
|
const gpio_num_t sck = (gpio_num_t)tbeam_supreme::sdSck();
|
||||||
|
const gpio_num_t miso = (gpio_num_t)tbeam_supreme::sdMiso();
|
||||||
|
const gpio_num_t mosi = (gpio_num_t)tbeam_supreme::sdMosi();
|
||||||
|
logf("PINS(%s): CS=%d SCK=%d MISO=%d MOSI=%d",
|
||||||
|
tag, gpio_get_level(cs), gpio_get_level(sck), gpio_get_level(miso), gpio_get_level(mosi));
|
||||||
|
}
|
||||||
|
|
||||||
|
bool StartupSdManager::initPmuForSdPower() {
|
||||||
|
if (!tbeam_supreme::initPmuForPeripherals(pmu_, &serial_)) {
|
||||||
|
logf("ERROR: PMU init failed");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void StartupSdManager::cycleSdRail(uint32_t offMs, uint32_t onSettleMs) {
|
||||||
|
if (!cfg_.enableSdRailCycle) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
if (!pmu_) {
|
||||||
|
logf("SD rail cycle skipped: pmu=null");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
forceSpiDeselected();
|
||||||
|
pmu_->disablePowerOutput(XPOWERS_BLDO1);
|
||||||
|
delay(offMs);
|
||||||
|
pmu_->setPowerChannelVoltage(XPOWERS_BLDO1, 3300);
|
||||||
|
pmu_->enablePowerOutput(XPOWERS_BLDO1);
|
||||||
|
delay(onSettleMs);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool StartupSdManager::tryMountWithBus(SPIClass& bus, const char* busName, uint32_t hz, bool verbose) {
|
||||||
|
SD.end();
|
||||||
|
bus.end();
|
||||||
|
delay(10);
|
||||||
|
forceSpiDeselected();
|
||||||
|
|
||||||
|
bus.begin(tbeam_supreme::sdSck(), tbeam_supreme::sdMiso(), tbeam_supreme::sdMosi(), tbeam_supreme::sdCs());
|
||||||
|
digitalWrite(tbeam_supreme::sdCs(), HIGH);
|
||||||
|
delay(2);
|
||||||
|
for (int i = 0; i < 10; i++) {
|
||||||
|
bus.transfer(0xFF);
|
||||||
|
}
|
||||||
|
delay(2);
|
||||||
|
|
||||||
|
if (verbose) {
|
||||||
|
logf("SD: trying bus=%s freq=%lu Hz", busName, (unsigned long)hz);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!SD.begin(tbeam_supreme::sdCs(), bus, hz)) {
|
||||||
|
if (verbose) {
|
||||||
|
logf("SD: mount failed (possible non-FAT format, power, or bus issue)");
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (SD.cardType() == CARD_NONE) {
|
||||||
|
SD.end();
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
sdSpi_ = &bus;
|
||||||
|
sdBusName_ = busName;
|
||||||
|
sdFreq_ = hz;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool StartupSdManager::mountPreferred(bool verbose) {
|
||||||
|
return tryMountWithBus(sdSpiH_, "HSPI", 400000, verbose);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool StartupSdManager::mountCardFullScan() {
|
||||||
|
const uint32_t freqs[] = {400000, 1000000, 4000000, 10000000};
|
||||||
|
|
||||||
|
for (uint8_t i = 0; i < (sizeof(freqs) / sizeof(freqs[0])); ++i) {
|
||||||
|
if (tryMountWithBus(sdSpiH_, "HSPI", freqs[i], true)) {
|
||||||
|
logf("SD: card detected and mounted");
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
for (uint8_t i = 0; i < (sizeof(freqs) / sizeof(freqs[0])); ++i) {
|
||||||
|
if (tryMountWithBus(sdSpiF_, "FSPI", freqs[i], true)) {
|
||||||
|
logf("SD: card detected and mounted");
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
logf("SD: begin() failed on all bus/frequency attempts");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool StartupSdManager::verifyMountedCard() {
|
||||||
|
File root = SD.open("/", FILE_READ);
|
||||||
|
if (!root) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
root.close();
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
const char* StartupSdManager::cardTypeToString(uint8_t type) {
|
||||||
|
switch (type) {
|
||||||
|
case CARD_MMC:
|
||||||
|
return "MMC";
|
||||||
|
case CARD_SD:
|
||||||
|
return "SDSC";
|
||||||
|
case CARD_SDHC:
|
||||||
|
return "SDHC/SDXC";
|
||||||
|
default:
|
||||||
|
return "UNKNOWN";
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void StartupSdManager::printCardInfo() {
|
||||||
|
uint8_t cardType = SD.cardType();
|
||||||
|
uint64_t cardSizeMB = SD.cardSize() / (1024ULL * 1024ULL);
|
||||||
|
uint64_t totalMB = SD.totalBytes() / (1024ULL * 1024ULL);
|
||||||
|
uint64_t usedMB = SD.usedBytes() / (1024ULL * 1024ULL);
|
||||||
|
|
||||||
|
logf("SD type: %s", cardTypeToString(cardType));
|
||||||
|
logf("SD size: %llu MB", cardSizeMB);
|
||||||
|
logf("FS total: %llu MB", totalMB);
|
||||||
|
logf("FS used : %llu MB", usedMB);
|
||||||
|
logf("SPI bus: %s @ %lu Hz", sdBusName_, (unsigned long)sdFreq_);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool StartupSdManager::ensureDirRecursive(const char* path) {
|
||||||
|
String full(path);
|
||||||
|
if (!full.startsWith("/")) {
|
||||||
|
full = "/" + full;
|
||||||
|
}
|
||||||
|
|
||||||
|
int start = 1;
|
||||||
|
while (start > 0 && start < (int)full.length()) {
|
||||||
|
int slash = full.indexOf('/', start);
|
||||||
|
String partial = (slash < 0) ? full : full.substring(0, slash);
|
||||||
|
if (!SD.exists(partial.c_str()) && !SD.mkdir(partial.c_str())) {
|
||||||
|
logf("ERROR: mkdir failed for %s", partial.c_str());
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (slash < 0) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
start = slash + 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool StartupSdManager::rewriteFile(const char* path, const char* payload) {
|
||||||
|
if (SD.exists(path) && !SD.remove(path)) {
|
||||||
|
logf("ERROR: failed to erase %s", path);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
File f = SD.open(path, FILE_WRITE);
|
||||||
|
if (!f) {
|
||||||
|
logf("ERROR: failed to create %s", path);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t wrote = f.println(payload);
|
||||||
|
f.close();
|
||||||
|
if (wrote == 0) {
|
||||||
|
logf("ERROR: write failed for %s", path);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void StartupSdManager::permissionsDemo(const char* path) {
|
||||||
|
logf("Permissions demo: FAT has no Unix chmod/chown, use open mode only.");
|
||||||
|
File r = SD.open(path, FILE_READ);
|
||||||
|
if (!r) {
|
||||||
|
logf("Could not open %s as FILE_READ", path);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
size_t writeInReadMode = r.print("attempt write while opened read-only");
|
||||||
|
if (writeInReadMode == 0) {
|
||||||
|
logf("As expected, FILE_READ write was blocked.");
|
||||||
|
} else {
|
||||||
|
logf("NOTE: FILE_READ write returned %u (unexpected)", (unsigned)writeInReadMode);
|
||||||
|
}
|
||||||
|
r.close();
|
||||||
|
}
|
||||||
|
|
||||||
|
void StartupSdManager::setStateMounted() {
|
||||||
|
if (watchState_ != SdWatchState::MOUNTED) {
|
||||||
|
logf("EVENT: card inserted/mounted");
|
||||||
|
mountedEventPending_ = true;
|
||||||
|
notify(SdEvent::CARD_MOUNTED, "SD card mounted");
|
||||||
|
}
|
||||||
|
watchState_ = SdWatchState::MOUNTED;
|
||||||
|
}
|
||||||
|
|
||||||
|
void StartupSdManager::setStateAbsent() {
|
||||||
|
if (watchState_ == SdWatchState::MOUNTED) {
|
||||||
|
logf("EVENT: card removed/unavailable");
|
||||||
|
removedEventPending_ = true;
|
||||||
|
notify(SdEvent::CARD_REMOVED, "SD card removed");
|
||||||
|
} else if (watchState_ != SdWatchState::ABSENT) {
|
||||||
|
logf("EVENT: no card detected");
|
||||||
|
notify(SdEvent::NO_CARD, "Missing SD card or invalid FAT16/FAT32 format");
|
||||||
|
}
|
||||||
|
SD.end();
|
||||||
|
watchState_ = SdWatchState::ABSENT;
|
||||||
|
}
|
||||||
90
exercises/18_GPS_Field_QA/lib/startup_sd/StartupSdManager.h
Normal file
90
exercises/18_GPS_Field_QA/lib/startup_sd/StartupSdManager.h
Normal file
|
|
@ -0,0 +1,90 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include <SD.h>
|
||||||
|
#include <SPI.h>
|
||||||
|
#include <Wire.h>
|
||||||
|
#include "tbeam_supreme_adapter.h"
|
||||||
|
|
||||||
|
enum class SdWatchState : uint8_t {
|
||||||
|
UNKNOWN = 0,
|
||||||
|
ABSENT,
|
||||||
|
MOUNTED
|
||||||
|
};
|
||||||
|
|
||||||
|
enum class SdEvent : uint8_t {
|
||||||
|
NO_CARD,
|
||||||
|
CARD_MOUNTED,
|
||||||
|
CARD_REMOVED
|
||||||
|
};
|
||||||
|
|
||||||
|
using SdStatusCallback = void (*)(SdEvent event, const char* message);
|
||||||
|
|
||||||
|
struct SdWatcherConfig {
|
||||||
|
bool enableSdRailCycle = true;
|
||||||
|
bool enablePinDumps = true;
|
||||||
|
bool recoveryRailCycleOnFullScan = true;
|
||||||
|
uint32_t recoveryRailOffMs = 250;
|
||||||
|
uint32_t recoveryRailOnSettleMs = 700;
|
||||||
|
uint32_t startupWarmupMs = 1500;
|
||||||
|
uint32_t pollIntervalAbsentMs = 1000;
|
||||||
|
uint32_t pollIntervalMountedMs = 2000;
|
||||||
|
uint32_t fullScanIntervalMs = 10000;
|
||||||
|
uint8_t votesToPresent = 2;
|
||||||
|
uint8_t votesToAbsent = 5;
|
||||||
|
};
|
||||||
|
|
||||||
|
class StartupSdManager {
|
||||||
|
public:
|
||||||
|
explicit StartupSdManager(Print& serial = Serial);
|
||||||
|
|
||||||
|
bool begin(const SdWatcherConfig& cfg, SdStatusCallback callback = nullptr);
|
||||||
|
void update();
|
||||||
|
|
||||||
|
bool isMounted() const { return watchState_ == SdWatchState::MOUNTED; }
|
||||||
|
SdWatchState state() const { return watchState_; }
|
||||||
|
|
||||||
|
bool consumeMountedEvent();
|
||||||
|
bool consumeRemovedEvent();
|
||||||
|
|
||||||
|
void printCardInfo();
|
||||||
|
bool ensureDirRecursive(const char* path);
|
||||||
|
bool rewriteFile(const char* path, const char* payload);
|
||||||
|
void permissionsDemo(const char* path);
|
||||||
|
|
||||||
|
private:
|
||||||
|
void logf(const char* fmt, ...);
|
||||||
|
void notify(SdEvent event, const char* message);
|
||||||
|
void forceSpiDeselected();
|
||||||
|
void dumpSdPins(const char* tag);
|
||||||
|
bool initPmuForSdPower();
|
||||||
|
void cycleSdRail(uint32_t offMs = 250, uint32_t onSettleMs = 600);
|
||||||
|
bool tryMountWithBus(SPIClass& bus, const char* busName, uint32_t hz, bool verbose);
|
||||||
|
bool mountPreferred(bool verbose);
|
||||||
|
bool mountCardFullScan();
|
||||||
|
bool verifyMountedCard();
|
||||||
|
const char* cardTypeToString(uint8_t type);
|
||||||
|
void setStateMounted();
|
||||||
|
void setStateAbsent();
|
||||||
|
|
||||||
|
Print& serial_;
|
||||||
|
SdWatcherConfig cfg_{};
|
||||||
|
SdStatusCallback callback_ = nullptr;
|
||||||
|
|
||||||
|
SPIClass sdSpiH_{HSPI};
|
||||||
|
SPIClass sdSpiF_{FSPI};
|
||||||
|
SPIClass* sdSpi_ = nullptr;
|
||||||
|
const char* sdBusName_ = "none";
|
||||||
|
uint32_t sdFreq_ = 0;
|
||||||
|
XPowersLibInterface* pmu_ = nullptr;
|
||||||
|
|
||||||
|
SdWatchState watchState_ = SdWatchState::UNKNOWN;
|
||||||
|
uint8_t presentVotes_ = 0;
|
||||||
|
uint8_t absentVotes_ = 0;
|
||||||
|
uint32_t lastPollMs_ = 0;
|
||||||
|
uint32_t lastFullScanMs_ = 0;
|
||||||
|
uint32_t logSeq_ = 0;
|
||||||
|
|
||||||
|
bool mountedEventPending_ = false;
|
||||||
|
bool removedEventPending_ = false;
|
||||||
|
};
|
||||||
12
exercises/18_GPS_Field_QA/lib/startup_sd/library.json
Normal file
12
exercises/18_GPS_Field_QA/lib/startup_sd/library.json
Normal file
|
|
@ -0,0 +1,12 @@
|
||||||
|
{
|
||||||
|
"name": "startup_sd",
|
||||||
|
"version": "0.1.0",
|
||||||
|
"dependencies": [
|
||||||
|
{
|
||||||
|
"name": "XPowersLib"
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"name": "Wire"
|
||||||
|
}
|
||||||
|
]
|
||||||
|
}
|
||||||
|
|
@ -2,7 +2,7 @@
|
||||||
; Exercise 18_GPS_Field_QA
|
; Exercise 18_GPS_Field_QA
|
||||||
|
|
||||||
[platformio]
|
[platformio]
|
||||||
default_envs = amy
|
default_envs = cy
|
||||||
|
|
||||||
[env]
|
[env]
|
||||||
platform = espressif32
|
platform = espressif32
|
||||||
|
|
|
||||||
|
|
@ -1,16 +1,21 @@
|
||||||
// 20260405 ChatGPT
|
// 20260406 ChatGPT
|
||||||
// Exercise 18_GPS_Field_QA
|
// Exercise 18_GPS_Field_QA
|
||||||
|
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include <SPIFFS.h>
|
#include <ctype.h>
|
||||||
|
#include <SPI.h>
|
||||||
|
#include <SD.h>
|
||||||
|
#include <strings.h>
|
||||||
#include <Wire.h>
|
#include <Wire.h>
|
||||||
#include <WiFi.h>
|
#include <WiFi.h>
|
||||||
#include <WebServer.h>
|
#include <WebServer.h>
|
||||||
|
|
||||||
|
#include "ClockDiscipline.h"
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "DisplayManager.h"
|
#include "DisplayManager.h"
|
||||||
#include "GnssManager.h"
|
#include "GnssManager.h"
|
||||||
#include "RunStats.h"
|
#include "RunStats.h"
|
||||||
|
#include "StartupSdManager.h"
|
||||||
#include "StorageManager.h"
|
#include "StorageManager.h"
|
||||||
#include "tbeam_supreme_adapter.h"
|
#include "tbeam_supreme_adapter.h"
|
||||||
|
|
||||||
|
|
@ -18,143 +23,88 @@ using namespace field_qa;
|
||||||
|
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
struct RtcDateTime {
|
|
||||||
uint16_t year;
|
|
||||||
uint8_t month;
|
|
||||||
uint8_t day;
|
|
||||||
uint8_t hour;
|
|
||||||
uint8_t minute;
|
|
||||||
uint8_t second;
|
|
||||||
};
|
|
||||||
|
|
||||||
XPowersLibInterface* g_pmu = nullptr;
|
XPowersLibInterface* g_pmu = nullptr;
|
||||||
DisplayManager g_display;
|
DisplayManager g_display;
|
||||||
GnssManager g_gnss;
|
GnssManager g_gnss;
|
||||||
|
ClockDiscipline g_clock;
|
||||||
StorageManager g_storage;
|
StorageManager g_storage;
|
||||||
RunStats g_stats;
|
RunStats g_stats;
|
||||||
|
StartupSdManager g_sd(Serial);
|
||||||
WebServer g_server(80);
|
WebServer g_server(80);
|
||||||
|
|
||||||
char g_runId[48] = {0};
|
char g_runId[48] = {0};
|
||||||
char g_bootTimestampUtc[32] = {0};
|
char g_bootTimestampUtc[32] = {0};
|
||||||
char g_serialLine[128] = {0};
|
char g_serialLine[160] = {0};
|
||||||
char g_apSsid[32] = {0};
|
char g_apSsid[32] = {0};
|
||||||
size_t g_serialLineLen = 0;
|
size_t g_serialLineLen = 0;
|
||||||
|
|
||||||
|
bool g_clockDisciplined = false;
|
||||||
bool g_loggingEnabled = false;
|
bool g_loggingEnabled = false;
|
||||||
bool g_periodicSerialEnabled = false;
|
bool g_periodicSerialEnabled = false;
|
||||||
bool g_storageReady = false;
|
bool g_storageReady = false;
|
||||||
bool g_storageMounted = false;
|
bool g_storageMounted = false;
|
||||||
bool g_webReady = false;
|
bool g_webReady = false;
|
||||||
size_t g_logFileCount = 0;
|
size_t g_logFileCount = 0;
|
||||||
|
uint32_t g_sampleSeq = 0;
|
||||||
|
uint32_t g_runStartMs = 0;
|
||||||
|
|
||||||
uint32_t g_lastSampleMs = 0;
|
uint32_t g_lastSampleMs = 0;
|
||||||
uint32_t g_lastFlushMs = 0;
|
uint32_t g_lastFlushMs = 0;
|
||||||
uint32_t g_lastDisplayMs = 0;
|
uint32_t g_lastDisplayMs = 0;
|
||||||
uint32_t g_lastStatusMs = 0;
|
uint32_t g_lastStatusMs = 0;
|
||||||
|
uint32_t g_lastDisciplineAttemptMs = 0;
|
||||||
|
volatile uint32_t g_ppsEdgeCount = 0;
|
||||||
|
|
||||||
uint8_t fromBcd(uint8_t b) {
|
void IRAM_ATTR onPpsEdge() {
|
||||||
return ((b >> 4U) * 10U) + (b & 0x0FU);
|
++g_ppsEdgeCount;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool rtcRead(RtcDateTime& out, bool& lowVoltageFlag) {
|
String htmlEscape(const String& in) {
|
||||||
Wire1.beginTransmission(RTC_I2C_ADDR);
|
String out;
|
||||||
Wire1.write(0x02);
|
out.reserve(in.length() + 16);
|
||||||
if (Wire1.endTransmission(false) != 0) {
|
for (size_t i = 0; i < in.length(); ++i) {
|
||||||
return false;
|
const char c = in[i];
|
||||||
|
if (c == '&') out += "&";
|
||||||
|
else if (c == '<') out += "<";
|
||||||
|
else if (c == '>') out += ">";
|
||||||
|
else if (c == '"') out += """;
|
||||||
|
else out += c;
|
||||||
}
|
}
|
||||||
|
return out;
|
||||||
const uint8_t need = 7;
|
|
||||||
uint8_t got = Wire1.requestFrom((int)RTC_I2C_ADDR, (int)need);
|
|
||||||
if (got != need) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t sec = Wire1.read();
|
|
||||||
uint8_t min = Wire1.read();
|
|
||||||
uint8_t hour = Wire1.read();
|
|
||||||
uint8_t day = Wire1.read();
|
|
||||||
(void)Wire1.read();
|
|
||||||
uint8_t month = Wire1.read();
|
|
||||||
uint8_t year = Wire1.read();
|
|
||||||
|
|
||||||
lowVoltageFlag = (sec & 0x80U) != 0;
|
|
||||||
out.second = fromBcd(sec & 0x7FU);
|
|
||||||
out.minute = fromBcd(min & 0x7FU);
|
|
||||||
out.hour = fromBcd(hour & 0x3FU);
|
|
||||||
out.day = fromBcd(day & 0x3FU);
|
|
||||||
out.month = fromBcd(month & 0x1FU);
|
|
||||||
uint8_t yy = fromBcd(year);
|
|
||||||
bool century = (month & 0x80U) != 0;
|
|
||||||
out.year = century ? (1900U + yy) : (2000U + yy);
|
|
||||||
return true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool readBootTimestampFromRtc(char* isoOut, size_t isoOutSize, char* runIdOut, size_t runIdOutSize) {
|
String urlEncode(const String& in) {
|
||||||
RtcDateTime now{};
|
String out;
|
||||||
bool low = false;
|
char hex[4];
|
||||||
if (!rtcRead(now, low)) {
|
for (size_t i = 0; i < in.length(); ++i) {
|
||||||
return false;
|
const unsigned char c = (unsigned char)in[i];
|
||||||
}
|
if (isalnum(c) || c == '-' || c == '_' || c == '.' || c == '/' || c == '~') {
|
||||||
snprintf(isoOut,
|
out += (char)c;
|
||||||
isoOutSize,
|
|
||||||
"%04u-%02u-%02uT%02u:%02u:%02uZ",
|
|
||||||
(unsigned)now.year,
|
|
||||||
(unsigned)now.month,
|
|
||||||
(unsigned)now.day,
|
|
||||||
(unsigned)now.hour,
|
|
||||||
(unsigned)now.minute,
|
|
||||||
(unsigned)now.second);
|
|
||||||
snprintf(runIdOut,
|
|
||||||
runIdOutSize,
|
|
||||||
"%04u%02u%02u_%02u%02u%02u_%s",
|
|
||||||
(unsigned)now.year,
|
|
||||||
(unsigned)now.month,
|
|
||||||
(unsigned)now.day,
|
|
||||||
(unsigned)now.hour,
|
|
||||||
(unsigned)now.minute,
|
|
||||||
(unsigned)now.second,
|
|
||||||
kBoardId);
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void formatUtcNowFallback(char* out, size_t outSize) {
|
|
||||||
const uint32_t sec = millis() / 1000U;
|
|
||||||
const uint32_t hh = sec / 3600U;
|
|
||||||
const uint32_t mm = (sec % 3600U) / 60U;
|
|
||||||
const uint32_t ss = sec % 60U;
|
|
||||||
snprintf(out, outSize, "uptime_%02lu%02lu%02lu", (unsigned long)hh, (unsigned long)mm, (unsigned long)ss);
|
|
||||||
}
|
|
||||||
|
|
||||||
void setBootTimestampFromSample(const GnssSample& sample) {
|
|
||||||
if (g_bootTimestampUtc[0] != '\0' || !sample.validTime) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
snprintf(g_bootTimestampUtc,
|
|
||||||
sizeof(g_bootTimestampUtc),
|
|
||||||
"%04u-%02u-%02uT%02u:%02u:%02uZ",
|
|
||||||
(unsigned)sample.year,
|
|
||||||
(unsigned)sample.month,
|
|
||||||
(unsigned)sample.day,
|
|
||||||
(unsigned)sample.hour,
|
|
||||||
(unsigned)sample.minute,
|
|
||||||
(unsigned)sample.second);
|
|
||||||
}
|
|
||||||
|
|
||||||
void makeRunId(const GnssSample* sample) {
|
|
||||||
if (sample && sample->validTime) {
|
|
||||||
snprintf(g_runId,
|
|
||||||
sizeof(g_runId),
|
|
||||||
"%04u%02u%02u_%02u%02u%02u_%s",
|
|
||||||
(unsigned)sample->year,
|
|
||||||
(unsigned)sample->month,
|
|
||||||
(unsigned)sample->day,
|
|
||||||
(unsigned)sample->hour,
|
|
||||||
(unsigned)sample->minute,
|
|
||||||
(unsigned)sample->second,
|
|
||||||
kBoardId);
|
|
||||||
} else {
|
} else {
|
||||||
char stamp[24];
|
snprintf(hex, sizeof(hex), "%%%02X", c);
|
||||||
formatUtcNowFallback(stamp, sizeof(stamp));
|
out += hex;
|
||||||
snprintf(g_runId, sizeof(g_runId), "%s_%s", stamp, kBoardId);
|
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
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() {
|
void printProvenance() {
|
||||||
|
|
@ -166,18 +116,18 @@ void printProvenance() {
|
||||||
Serial.printf("storage=%s\n", kStorageName);
|
Serial.printf("storage=%s\n", kStorageName);
|
||||||
Serial.printf("sample_period_ms=%lu\n", (unsigned long)kSamplePeriodMs);
|
Serial.printf("sample_period_ms=%lu\n", (unsigned long)kSamplePeriodMs);
|
||||||
Serial.printf("log_period_ms=%lu\n", (unsigned long)kLogFlushPeriodMs);
|
Serial.printf("log_period_ms=%lu\n", (unsigned long)kLogFlushPeriodMs);
|
||||||
Serial.printf("run_id=%s\n", g_runId);
|
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_ssid=%s\n", g_apSsid);
|
||||||
Serial.printf("web_url=http://192.168.%u.1/\n", (unsigned)kLogApIpOctet);
|
Serial.printf("web_url=http://192.168.%u.1/\n", (unsigned)kLogApIpOctet);
|
||||||
}
|
}
|
||||||
|
|
||||||
void printSummary() {
|
void printSummary() {
|
||||||
const String currentPath = String(g_storage.currentPath());
|
|
||||||
File rootDir = SPIFFS.open("/");
|
|
||||||
const bool rootDirOk = rootDir && rootDir.isDirectory();
|
|
||||||
Serial.println("summary:");
|
Serial.println("summary:");
|
||||||
Serial.printf("build=%s\n", kFirmwareVersion);
|
Serial.printf("build=%s\n", kFirmwareVersion);
|
||||||
Serial.printf("run_id=%s\n", g_runId);
|
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("elapsed_ms=%lu\n", (unsigned long)g_stats.elapsedMs(millis()));
|
||||||
Serial.printf("ttff_ms=%lu\n", (unsigned long)g_stats.ttffMs());
|
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("longest_no_fix_ms=%lu\n", (unsigned long)g_stats.longestNoFixMs());
|
||||||
|
|
@ -187,15 +137,10 @@ void printSummary() {
|
||||||
Serial.printf("storage_log_dir=%s\n", kLogDir);
|
Serial.printf("storage_log_dir=%s\n", kLogDir);
|
||||||
Serial.printf("log_file=%s\n", g_storage.currentPath());
|
Serial.printf("log_file=%s\n", g_storage.currentPath());
|
||||||
Serial.printf("storage_file_open=%s\n", g_storage.fileOpen() ? "yes" : "no");
|
Serial.printf("storage_file_open=%s\n", g_storage.fileOpen() ? "yes" : "no");
|
||||||
Serial.printf("storage_path_len=%u\n", (unsigned)currentPath.length());
|
Serial.printf("storage_total_bytes=%u\n", g_storageMounted ? (unsigned)SD.totalBytes() : 0U);
|
||||||
Serial.printf("storage_path_exists=%s\n",
|
Serial.printf("storage_used_bytes=%u\n", g_storageMounted ? (unsigned)SD.usedBytes() : 0U);
|
||||||
(!currentPath.isEmpty() && SPIFFS.exists(currentPath)) ? "yes" : "no");
|
|
||||||
Serial.printf("storage_root_dir=%s\n", rootDirOk ? "yes" : "no");
|
|
||||||
Serial.printf("storage_total_bytes=%u\n", (unsigned)SPIFFS.totalBytes());
|
|
||||||
Serial.printf("storage_used_bytes=%u\n", (unsigned)SPIFFS.usedBytes());
|
|
||||||
Serial.printf("storage_buffered_bytes=%u\n", (unsigned)g_storage.bufferedBytes());
|
Serial.printf("storage_buffered_bytes=%u\n", (unsigned)g_storage.bufferedBytes());
|
||||||
Serial.printf("storage_log_count=%u\n", (unsigned)g_logFileCount);
|
Serial.printf("storage_log_count=%u\n", (unsigned)g_logFileCount);
|
||||||
Serial.printf("storage_auto_log_limit=%u\n", (unsigned)kMaxLogFilesBeforePause);
|
|
||||||
Serial.printf("web_ready=%s\n", g_webReady ? "yes" : "no");
|
Serial.printf("web_ready=%s\n", g_webReady ? "yes" : "no");
|
||||||
Serial.printf("web_url=http://192.168.%u.1/\n", (unsigned)kLogApIpOctet);
|
Serial.printf("web_url=http://192.168.%u.1/\n", (unsigned)kLogApIpOctet);
|
||||||
}
|
}
|
||||||
|
|
@ -215,10 +160,9 @@ void printStatusLine(const GnssSample& sample) {
|
||||||
} else {
|
} else {
|
||||||
strlcpy(ts, "NO_UTC", sizeof(ts));
|
strlcpy(ts, "NO_UTC", sizeof(ts));
|
||||||
}
|
}
|
||||||
Serial.printf("%s board=%s chip=%s fix=%s used=%d view=%d hdop=%s lat=%s lon=%s alt=%s q=%s\n",
|
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,
|
ts,
|
||||||
kBoardId,
|
kBoardId,
|
||||||
g_gnss.detectedChipName(),
|
|
||||||
fixTypeToString(sample.fixType),
|
fixTypeToString(sample.fixType),
|
||||||
sample.satsUsed < 0 ? 0 : sample.satsUsed,
|
sample.satsUsed < 0 ? 0 : sample.satsUsed,
|
||||||
sample.satsInView < 0 ? 0 : sample.satsInView,
|
sample.satsInView < 0 ? 0 : sample.satsInView,
|
||||||
|
|
@ -226,134 +170,205 @@ void printStatusLine(const GnssSample& sample) {
|
||||||
sample.validLocation ? String(sample.latitude, 5).c_str() : "",
|
sample.validLocation ? String(sample.latitude, 5).c_str() : "",
|
||||||
sample.validLocation ? String(sample.longitude, 5).c_str() : "",
|
sample.validLocation ? String(sample.longitude, 5).c_str() : "",
|
||||||
sample.validAltitude ? String(sample.altitudeM, 1).c_str() : "",
|
sample.validAltitude ? String(sample.altitudeM, 1).c_str() : "",
|
||||||
qualityClassForSample(sample));
|
qualityClassForSample(sample),
|
||||||
|
g_clockDisciplined ? "disciplined" : "waiting",
|
||||||
|
g_loggingEnabled ? "on" : "off");
|
||||||
}
|
}
|
||||||
|
|
||||||
void handleCommand(const char* line) {
|
bool ensureStorageReady() {
|
||||||
if (!line || line[0] == '\0') {
|
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 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;
|
return;
|
||||||
}
|
}
|
||||||
Serial.printf("-->%s\n", line);
|
if ((uint32_t)(millis() - g_lastDisciplineAttemptMs) < kClockDisciplineRetryMs) {
|
||||||
if (strcasecmp(line, "status") == 0) {
|
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();
|
GnssSample sample = g_gnss.makeSample();
|
||||||
sample.longestNoFixMs = g_stats.longestNoFixMs();
|
g_stats.updateFromSample(sample, millis());
|
||||||
sample.ttffMs = g_stats.ttffMs();
|
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);
|
printStatusLine(sample);
|
||||||
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("log_file=%s\n", g_storage.currentPath());
|
|
||||||
Serial.printf("storage_log_count=%u\n", (unsigned)g_logFileCount);
|
|
||||||
Serial.printf("periodic_serial=%s\n", g_periodicSerialEnabled ? "on" : "off");
|
|
||||||
Serial.printf("web_ready=%s\n", g_webReady ? "yes" : "no");
|
|
||||||
Serial.printf("web_url=http://192.168.%u.1/\n", (unsigned)kLogApIpOctet);
|
|
||||||
} else if (strcasecmp(line, "summary") == 0) {
|
|
||||||
printSummary();
|
|
||||||
} else if (strcasecmp(line, "start") == 0) {
|
|
||||||
if (g_storageReady) {
|
|
||||||
g_loggingEnabled = true;
|
|
||||||
Serial.println("logging already active");
|
|
||||||
} else if (!g_storageMounted) {
|
|
||||||
Serial.println("storage not mounted");
|
|
||||||
} else if (g_storage.startLog(g_runId, g_bootTimestampUtc)) {
|
|
||||||
g_storageReady = true;
|
|
||||||
g_loggingEnabled = true;
|
|
||||||
g_logFileCount = g_storage.logFileCount();
|
|
||||||
Serial.println("logging started");
|
|
||||||
} else {
|
|
||||||
Serial.printf("logging start failed: %s\n", g_storage.lastError());
|
|
||||||
}
|
}
|
||||||
} else if (strcasecmp(line, "stop") == 0) {
|
if ((uint32_t)(millis() - g_lastDisplayMs) >= kDisplayPeriodMs) {
|
||||||
g_loggingEnabled = false;
|
g_lastDisplayMs = millis();
|
||||||
g_storage.flush();
|
if (g_clockDisciplined) {
|
||||||
Serial.println("logging stopped");
|
g_display.showSample(sample, g_stats);
|
||||||
} else if (strcasecmp(line, "quiet") == 0) {
|
|
||||||
g_periodicSerialEnabled = false;
|
|
||||||
Serial.println("periodic serial output disabled");
|
|
||||||
} else if (strcasecmp(line, "verbose") == 0) {
|
|
||||||
g_periodicSerialEnabled = true;
|
|
||||||
Serial.println("periodic serial output enabled");
|
|
||||||
} else if (strcasecmp(line, "flush") == 0) {
|
|
||||||
g_storage.flush();
|
|
||||||
Serial.println("log buffer flushed");
|
|
||||||
} else if (strcasecmp(line, "ls") == 0) {
|
|
||||||
g_storage.flush();
|
|
||||||
g_storage.listFiles(Serial);
|
|
||||||
} else if (strncasecmp(line, "cat ", 4) == 0) {
|
|
||||||
g_storage.flush();
|
|
||||||
g_storage.catFile(Serial, line + 4);
|
|
||||||
} else if (strcasecmp(line, "erase_logs") == 0) {
|
|
||||||
g_storage.eraseLogs(Serial);
|
|
||||||
g_logFileCount = g_storage.logFileCount();
|
|
||||||
} else {
|
} else {
|
||||||
Serial.println("commands: status quiet verbose flush start stop summary ls cat <filename> erase_logs");
|
g_display.showBoot("Waiting for GPS UTC", sample.validTime ? "Awaiting PPS" : "No valid time yet");
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
String htmlEscape(const String& in) {
|
void buildFileTreeHtml(String& html, const char* path) {
|
||||||
String out;
|
File dir = SD.open(path, FILE_READ);
|
||||||
out.reserve(in.length() + 16);
|
if (!dir || !dir.isDirectory()) {
|
||||||
for (size_t i = 0; i < in.length(); ++i) {
|
dir.close();
|
||||||
char c = in[i];
|
html += "<li>directory unavailable</li>";
|
||||||
if (c == '&') out += "&";
|
return;
|
||||||
else if (c == '<') out += "<";
|
|
||||||
else if (c == '>') out += ">";
|
|
||||||
else if (c == '"') out += """;
|
|
||||||
else out += c;
|
|
||||||
}
|
}
|
||||||
return out;
|
|
||||||
}
|
|
||||||
|
|
||||||
String urlEncode(const String& in) {
|
File entry = dir.openNextFile();
|
||||||
static const char* hex = "0123456789ABCDEF";
|
while (entry) {
|
||||||
String out;
|
const String name = entry.name();
|
||||||
out.reserve(in.length() * 3);
|
String leaf = name;
|
||||||
for (size_t i = 0; i < in.length(); ++i) {
|
const int slash = leaf.lastIndexOf('/');
|
||||||
uint8_t c = (uint8_t)in[i];
|
if (slash >= 0) {
|
||||||
if ((c >= 'A' && c <= 'Z') || (c >= 'a' && c <= 'z') ||
|
leaf.remove(0, slash + 1);
|
||||||
(c >= '0' && c <= '9') || c == '-' || c == '_' || c == '.' || c == '~') {
|
}
|
||||||
out += (char)c;
|
|
||||||
|
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 {
|
} else {
|
||||||
out += '%';
|
String parent = path ? String(path) : String("/");
|
||||||
out += hex[(c >> 4) & 0x0F];
|
if (parent.isEmpty()) {
|
||||||
out += hex[c & 0x0F];
|
parent = "/";
|
||||||
}
|
}
|
||||||
|
if (!parent.endsWith("/")) {
|
||||||
|
parent += "/";
|
||||||
}
|
}
|
||||||
return out;
|
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();
|
||||||
}
|
}
|
||||||
|
|
||||||
String normalizeLogPath(const String& name) {
|
bool normalizeWebPath(const String& input, String& out) {
|
||||||
if (name.isEmpty() || name.indexOf("..") >= 0) {
|
return g_storage.normalizePath(input.c_str(), out);
|
||||||
return "";
|
|
||||||
}
|
|
||||||
if (name[0] == '/') {
|
|
||||||
return name;
|
|
||||||
}
|
|
||||||
return String("/") + name;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void handleWebIndex() {
|
void handleWebIndex() {
|
||||||
g_storage.flush();
|
g_storage.flush();
|
||||||
String html;
|
String html;
|
||||||
html.reserve(4096);
|
html.reserve(8192);
|
||||||
html += "<!doctype html><html><head><meta charset='utf-8'><title>GPSQA ";
|
html += "<!doctype html><html><head><meta charset='utf-8'><title>GPSQA ";
|
||||||
html += kBoardId;
|
html += kBoardId;
|
||||||
html += "</title></head><body>";
|
html += "</title></head><body>";
|
||||||
html += "<h1>GPSQA ";
|
html += "<h1>GPSQA ";
|
||||||
html += kBoardId;
|
html += kBoardId;
|
||||||
html += "</h1>";
|
html += "</h1><p>";
|
||||||
html += "<p>Run ID: ";
|
html += "Clock disciplined: ";
|
||||||
html += htmlEscape(String(g_runId));
|
html += g_clockDisciplined ? "yes" : "no";
|
||||||
html += "<br>Build: ";
|
html += "<br>Run ID: ";
|
||||||
html += htmlEscape(String(kFirmwareVersion));
|
html += htmlEscape(g_runId[0] ? String(g_runId) : String("PENDING_CLOCK"));
|
||||||
html += "<br>Boot UTC: ";
|
html += "<br>Boot UTC: ";
|
||||||
html += htmlEscape(String(g_bootTimestampUtc[0] != '\0' ? g_bootTimestampUtc : "UNKNOWN"));
|
html += htmlEscape(g_bootTimestampUtc[0] ? String(g_bootTimestampUtc) : String("UNKNOWN"));
|
||||||
html += "<br>Board: ";
|
|
||||||
html += htmlEscape(String(kBoardId));
|
|
||||||
html += "<br>GNSS configured: ";
|
|
||||||
html += htmlEscape(String(kGnssChip));
|
|
||||||
html += "<br>GNSS detected: ";
|
|
||||||
html += htmlEscape(String(g_gnss.detectedChipName()));
|
|
||||||
html += "<br>Storage mounted: ";
|
html += "<br>Storage mounted: ";
|
||||||
html += g_storageMounted ? "yes" : "no";
|
html += g_storageMounted ? "yes" : "no";
|
||||||
html += "<br>Storage ready: ";
|
html += "<br>Storage ready: ";
|
||||||
|
|
@ -362,67 +377,53 @@ void handleWebIndex() {
|
||||||
html += htmlEscape(String(g_storage.lastError()));
|
html += htmlEscape(String(g_storage.lastError()));
|
||||||
html += "<br>Current log: ";
|
html += "<br>Current log: ";
|
||||||
html += htmlEscape(String(g_storage.currentPath()));
|
html += htmlEscape(String(g_storage.currentPath()));
|
||||||
html += "</p><ul>";
|
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?erase_logs=1'>erase_logs</a></p>";
|
||||||
|
html += "<h2>SD Tree</h2><ul>";
|
||||||
|
|
||||||
if (!g_storageMounted) {
|
if (!g_storageMounted) {
|
||||||
html += "<li>storage not mounted</li>";
|
html += "<li>SD not mounted</li>";
|
||||||
} else {
|
} else {
|
||||||
File dir = SPIFFS.open("/");
|
buildFileTreeHtml(html, "/");
|
||||||
if (!dir || !dir.isDirectory()) {
|
|
||||||
html += "<li>root directory unavailable</li>";
|
|
||||||
} else {
|
|
||||||
File file = dir.openNextFile();
|
|
||||||
if (!file) {
|
|
||||||
html += "<li>(no files)</li>";
|
|
||||||
}
|
|
||||||
while (file) {
|
|
||||||
String name = file.name();
|
|
||||||
if (name.endsWith(".csv") || name.endsWith(".tsv")) {
|
|
||||||
html += "<li><a href='/download?name=";
|
|
||||||
html += urlEncode(name);
|
|
||||||
html += "'>";
|
|
||||||
html += htmlEscape(name);
|
|
||||||
html += "</a> (";
|
|
||||||
html += String((unsigned)file.size());
|
|
||||||
html += " bytes)</li>";
|
|
||||||
}
|
|
||||||
file = dir.openNextFile();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
html += "</ul></body></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);
|
g_server.send(200, "text/html; charset=utf-8", html);
|
||||||
}
|
}
|
||||||
|
|
||||||
void handleWebDownload() {
|
void handleWebDownload() {
|
||||||
g_storage.flush();
|
g_storage.flush();
|
||||||
if (!g_server.hasArg("name")) {
|
String pathArg = g_server.hasArg("path") ? g_server.arg("path") : g_server.arg("name");
|
||||||
g_server.send(400, "text/plain", "missing name");
|
String fullPath;
|
||||||
|
if (!normalizeWebPath(pathArg, fullPath)) {
|
||||||
|
g_server.send(400, "text/plain", "invalid path");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
String fullPath = normalizeLogPath(g_server.arg("name"));
|
|
||||||
if (fullPath.isEmpty()) {
|
File file = SD.open(fullPath.c_str(), FILE_READ);
|
||||||
g_server.send(400, "text/plain", "invalid name");
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
File file = SPIFFS.open(fullPath, FILE_READ);
|
|
||||||
if (!file) {
|
if (!file) {
|
||||||
g_server.send(404, "text/plain", "not found");
|
g_server.send(404, "text/plain", "not found");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
String downloadName = file.name();
|
String downloadName = file.name();
|
||||||
int slash = downloadName.lastIndexOf('/');
|
const int slash = downloadName.lastIndexOf('/');
|
||||||
if (slash >= 0) {
|
if (slash >= 0) {
|
||||||
downloadName.remove(0, slash + 1);
|
downloadName.remove(0, slash + 1);
|
||||||
}
|
}
|
||||||
g_server.sendHeader("Content-Disposition", String("attachment; filename=\"") + downloadName + "\"");
|
g_server.sendHeader("Content-Disposition", String("attachment; filename=\"") + downloadName + "\"");
|
||||||
g_server.setContentLength(file.size());
|
g_server.setContentLength(file.size());
|
||||||
g_server.send(200, "text/csv; charset=utf-8", "");
|
g_server.send(200, "application/octet-stream", "");
|
||||||
WiFiClient client = g_server.client();
|
WiFiClient client = g_server.client();
|
||||||
uint8_t buffer[512];
|
uint8_t buffer[512];
|
||||||
while (file.available()) {
|
while (file.available()) {
|
||||||
size_t readBytes = file.read(buffer, sizeof(buffer));
|
const size_t readBytes = file.read(buffer, sizeof(buffer));
|
||||||
if (readBytes == 0) {
|
if (readBytes == 0) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
@ -431,74 +432,65 @@ void handleWebDownload() {
|
||||||
file.close();
|
file.close();
|
||||||
}
|
}
|
||||||
|
|
||||||
void handleWebDebugRead() {
|
void handleWebCommand() {
|
||||||
|
String response;
|
||||||
|
|
||||||
|
if (g_server.hasArg("erase")) {
|
||||||
g_storage.flush();
|
g_storage.flush();
|
||||||
if (!g_server.hasArg("name")) {
|
const String path = g_server.arg("erase");
|
||||||
g_server.send(400, "text/plain", "missing name\n");
|
if (g_storage.eraseFile(path.c_str())) {
|
||||||
return;
|
g_storageReady = g_storage.ready();
|
||||||
|
if (!g_storageReady) {
|
||||||
|
g_loggingEnabled = false;
|
||||||
}
|
}
|
||||||
String fullPath = normalizeLogPath(g_server.arg("name"));
|
g_logFileCount = g_storage.logFileCount();
|
||||||
if (fullPath.isEmpty()) {
|
response = String("erased ") + path;
|
||||||
g_server.send(400, "text/plain", "invalid name\n");
|
} else {
|
||||||
return;
|
response = String("erase failed: ") + g_storage.lastError();
|
||||||
}
|
}
|
||||||
File file = SPIFFS.open(fullPath, FILE_READ);
|
} else if (g_server.hasArg("erase_logs")) {
|
||||||
if (!file) {
|
|
||||||
g_server.send(404, "text/plain", String("open failed: ") + fullPath + "\n");
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
String out;
|
|
||||||
out.reserve(512);
|
|
||||||
out += "path=";
|
|
||||||
out += fullPath;
|
|
||||||
out += "\nsize=";
|
|
||||||
out += String((unsigned)file.size());
|
|
||||||
out += "\navailable_before=";
|
|
||||||
out += String((unsigned)file.available());
|
|
||||||
out += "\n";
|
|
||||||
|
|
||||||
char buf[129];
|
|
||||||
size_t count = file.readBytes(buf, sizeof(buf) - 1);
|
|
||||||
buf[count] = '\0';
|
|
||||||
out += "read_bytes=";
|
|
||||||
out += String((unsigned)count);
|
|
||||||
out += "\navailable_after=";
|
|
||||||
out += String((unsigned)file.available());
|
|
||||||
out += "\npreview_begin\n";
|
|
||||||
out += String(buf);
|
|
||||||
out += "\npreview_end\n";
|
|
||||||
file.close();
|
|
||||||
g_server.send(200, "text/plain; charset=utf-8", out);
|
|
||||||
}
|
|
||||||
|
|
||||||
void handleWebRaw() {
|
|
||||||
g_storage.flush();
|
g_storage.flush();
|
||||||
if (!g_server.hasArg("name")) {
|
g_storage.eraseLogs(Serial);
|
||||||
g_server.send(400, "text/plain", "missing name\n");
|
g_storageReady = g_storage.ready();
|
||||||
return;
|
if (!g_storageReady) {
|
||||||
|
g_loggingEnabled = false;
|
||||||
}
|
}
|
||||||
String fullPath = normalizeLogPath(g_server.arg("name"));
|
g_logFileCount = g_storage.logFileCount();
|
||||||
if (fullPath.isEmpty()) {
|
response = "logs erased";
|
||||||
g_server.send(400, "text/plain", "invalid name\n");
|
} else if (g_server.hasArg("flush")) {
|
||||||
return;
|
g_storage.flush();
|
||||||
|
response = "buffer flushed";
|
||||||
|
} else if (g_server.hasArg("stop")) {
|
||||||
|
g_loggingEnabled = false;
|
||||||
|
g_storage.flush();
|
||||||
|
response = "logging stopped";
|
||||||
|
} 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();
|
||||||
}
|
}
|
||||||
File file = SPIFFS.open(fullPath, FILE_READ);
|
} else if (g_server.hasArg("status")) {
|
||||||
if (!file) {
|
response.reserve(256);
|
||||||
g_server.send(404, "text/plain", "not found\n");
|
response += "clock_disciplined=";
|
||||||
return;
|
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";
|
||||||
|
} else {
|
||||||
|
response = "commands: status flush start stop erase=<path> erase_logs=1";
|
||||||
}
|
}
|
||||||
String body;
|
|
||||||
body.reserve(file.size() + 1);
|
g_server.send(200, "text/plain; charset=utf-8", response);
|
||||||
while (file.available()) {
|
|
||||||
int c = file.read();
|
|
||||||
if (c < 0) {
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
body += (char)c;
|
|
||||||
}
|
|
||||||
file.close();
|
|
||||||
g_server.send(200, "text/plain; charset=utf-8", body);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void startWebServer() {
|
void startWebServer() {
|
||||||
|
|
@ -516,15 +508,84 @@ void startWebServer() {
|
||||||
|
|
||||||
g_server.on("/", HTTP_GET, handleWebIndex);
|
g_server.on("/", HTTP_GET, handleWebIndex);
|
||||||
g_server.on("/download", HTTP_GET, handleWebDownload);
|
g_server.on("/download", HTTP_GET, handleWebDownload);
|
||||||
g_server.on("/debug_read", HTTP_GET, handleWebDebugRead);
|
g_server.on("/cmd", HTTP_GET, handleWebCommand);
|
||||||
g_server.on("/raw", HTTP_GET, handleWebRaw);
|
|
||||||
g_server.begin();
|
g_server.begin();
|
||||||
g_webReady = true;
|
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) {
|
||||||
|
g_loggingEnabled = false;
|
||||||
|
g_storage.flush();
|
||||||
|
Serial.println("logging stopped");
|
||||||
|
} 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 summary ls cat <path> erase <path> erase_logs discipline");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void pollSerialConsole() {
|
void pollSerialConsole() {
|
||||||
while (Serial.available() > 0) {
|
while (Serial.available() > 0) {
|
||||||
int c = Serial.read();
|
const int c = Serial.read();
|
||||||
if (c < 0) {
|
if (c < 0) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
@ -544,37 +605,6 @@ void pollSerialConsole() {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void sampleAndMaybeLog() {
|
|
||||||
GnssSample sample = g_gnss.makeSample();
|
|
||||||
g_stats.updateFromSample(sample, millis());
|
|
||||||
sample.ttffMs = g_stats.ttffMs();
|
|
||||||
sample.longestNoFixMs = g_stats.longestNoFixMs();
|
|
||||||
|
|
||||||
setBootTimestampFromSample(sample);
|
|
||||||
if (g_runId[0] == '\0') {
|
|
||||||
makeRunId(&sample);
|
|
||||||
}
|
|
||||||
if (g_bootTimestampUtc[0] == '\0') {
|
|
||||||
strlcpy(g_bootTimestampUtc, "UNKNOWN", sizeof(g_bootTimestampUtc));
|
|
||||||
}
|
|
||||||
|
|
||||||
if (g_loggingEnabled && g_storageReady) {
|
|
||||||
SatelliteInfo sats[kMaxSatellites];
|
|
||||||
size_t satCount = g_gnss.copySatellites(sats, kMaxSatellites);
|
|
||||||
g_storage.appendSampleTsv(sample, g_runId, g_bootTimestampUtc);
|
|
||||||
g_storage.appendSatelliteTsv(sample, 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();
|
|
||||||
g_display.showSample(sample, g_stats);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
} // namespace
|
} // namespace
|
||||||
|
|
||||||
void setup() {
|
void setup() {
|
||||||
|
|
@ -592,49 +622,45 @@ void setup() {
|
||||||
|
|
||||||
g_display.begin();
|
g_display.begin();
|
||||||
g_display.showBoot("Booting...", kBoardId);
|
g_display.showBoot("Booting...", kBoardId);
|
||||||
|
|
||||||
g_stats.begin(millis());
|
g_stats.begin(millis());
|
||||||
g_gnss.begin();
|
g_gnss.begin();
|
||||||
(void)g_gnss.probeAtStartup(Serial);
|
(void)g_gnss.probeAtStartup(Serial);
|
||||||
startWebServer();
|
startWebServer();
|
||||||
|
|
||||||
if (!readBootTimestampFromRtc(g_bootTimestampUtc, sizeof(g_bootTimestampUtc), g_runId, sizeof(g_runId))) {
|
SdWatcherConfig sdCfg;
|
||||||
makeRunId(nullptr);
|
if (!g_sd.begin(sdCfg)) {
|
||||||
strlcpy(g_bootTimestampUtc, "UNKNOWN", sizeof(g_bootTimestampUtc));
|
Serial.println("WARNING: SD watcher init failed");
|
||||||
}
|
}
|
||||||
g_storageMounted = false;
|
g_storageMounted = g_sd.isMounted();
|
||||||
g_storageReady = false;
|
if (g_storageMounted) {
|
||||||
g_storageMounted = g_storage.mount();
|
g_sd.printCardInfo();
|
||||||
g_storageMounted = g_storage.mounted();
|
|
||||||
g_logFileCount = g_storage.logFileCount();
|
|
||||||
if (!g_storageMounted) {
|
|
||||||
Serial.printf("ERROR: SPIFFS mount failed: %s\n", g_storage.lastError());
|
|
||||||
g_display.showError("SPIFFS mount failed");
|
|
||||||
} else if (g_logFileCount <= kMaxLogFilesBeforePause) {
|
|
||||||
g_storageReady = g_storage.startLog(g_runId, g_bootTimestampUtc);
|
|
||||||
if (g_storageReady) {
|
|
||||||
g_loggingEnabled = true;
|
|
||||||
} else {
|
|
||||||
Serial.printf("ERROR: log start failed: %s\n", g_storage.lastError());
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#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 {
|
} else {
|
||||||
Serial.printf("INFO: auto logging paused, log count %u exceeds limit %u\n",
|
Serial.println("RTC invalid at boot");
|
||||||
(unsigned)g_logFileCount,
|
|
||||||
(unsigned)kMaxLogFilesBeforePause);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
printProvenance();
|
printProvenance();
|
||||||
g_display.showBoot("Survey mode", g_loggingEnabled ? "Logging active" : "Logging paused");
|
g_display.showBoot("Waiting for GPS UTC", "No log before RTC set");
|
||||||
|
|
||||||
g_lastSampleMs = millis();
|
g_lastSampleMs = millis();
|
||||||
g_lastFlushMs = millis();
|
g_lastFlushMs = millis();
|
||||||
g_lastDisplayMs = 0;
|
|
||||||
g_lastStatusMs = 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop() {
|
void loop() {
|
||||||
pollSerialConsole();
|
pollSerialConsole();
|
||||||
g_gnss.poll();
|
g_gnss.poll();
|
||||||
|
handleSdStateTransitions();
|
||||||
g_server.handleClient();
|
g_server.handleClient();
|
||||||
|
|
||||||
const uint32_t now = millis();
|
const uint32_t now = millis();
|
||||||
|
|
|
||||||
|
|
@ -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?)
|
You can read and write to SD cards that are FAT formatted. (Can they be Linux formatted?)
|
||||||
## Real Time Clock ("RTC")
|
## Real Time Clock ("RTC")
|
||||||
## Microphone
|
## 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
|
||||||
|
|
||||||
|
|
||||||
|
|
|
||||||
Loading…
Add table
Add a link
Reference in a new issue