fix gps sync
This commit is contained in:
parent
3969c5780d
commit
e5baa7cec5
|
|
@ -20,49 +20,61 @@ static const char *TAG = "GPS_SYNC";
|
|||
static uart_port_t gps_uart_num = UART_NUM_1;
|
||||
static int64_t monotonic_offset_us = 0;
|
||||
static volatile int64_t last_pps_monotonic = 0;
|
||||
static volatile time_t next_pps_gps_second = 0;
|
||||
static bool gps_has_fix = false;
|
||||
static bool use_gps_for_logs = false;
|
||||
static SemaphoreHandle_t sync_mutex;
|
||||
static volatile bool force_sync_update = true;
|
||||
|
||||
// PPS interrupt
|
||||
// Stores the monotonic time of the rising edge of the PPS signal
|
||||
static void IRAM_ATTR pps_isr_handler(void* arg) {
|
||||
static bool onetime = true;
|
||||
last_pps_monotonic = esp_timer_get_time();
|
||||
if (onetime) {
|
||||
esp_rom_printf("PPS connected!\n");
|
||||
onetime = false;
|
||||
}
|
||||
// Capture time immediately
|
||||
int64_t now = esp_timer_get_time();
|
||||
last_pps_monotonic = now;
|
||||
}
|
||||
|
||||
// Parse GPS time from NMEA
|
||||
// Parse GPS time from NMEA (GPRMC or GNRMC)
|
||||
static bool parse_gprmc(const char* nmea, struct tm* tm_out, bool* valid) {
|
||||
// Check Header
|
||||
if (strncmp(nmea, "$GPRMC", 6) != 0 && strncmp(nmea, "$GNRMC", 6) != 0) return false;
|
||||
|
||||
// Find Time Field
|
||||
char *p = strchr(nmea, ',');
|
||||
if (!p) return false;
|
||||
p++;
|
||||
p++; // Move past comma
|
||||
|
||||
int hour, min, sec;
|
||||
// Scan %2d%2d%2d effectively, using floats can be safer for sub-seconds but int is fine for PPS
|
||||
if (sscanf(p, "%2d%2d%2d", &hour, &min, &sec) != 3) return false;
|
||||
|
||||
// Find Status Field (A=Active/Valid, V=Void)
|
||||
p = strchr(p, ',');
|
||||
if (!p) return false;
|
||||
p++;
|
||||
*valid = (*p == 'A');
|
||||
|
||||
// Skip Latitude, N/S, Longitude, E/W, Speed, Course (6 fields)
|
||||
for (int i = 0; i < 7; i++) {
|
||||
p = strchr(p, ',');
|
||||
if (!p) return false;
|
||||
p++;
|
||||
}
|
||||
|
||||
// Date Field
|
||||
int day, month, year;
|
||||
if (sscanf(p, "%2d%2d%2d", &day, &month, &year) != 3) return false;
|
||||
|
||||
// Adjust Year (NMEA provides 2 digits)
|
||||
year += (year < 80) ? 2000 : 1900;
|
||||
|
||||
tm_out->tm_sec = sec;
|
||||
tm_out->tm_min = min;
|
||||
tm_out->tm_hour = hour;
|
||||
tm_out->tm_mday = day;
|
||||
tm_out->tm_mon = month - 1;
|
||||
tm_out->tm_year = year - 1900;
|
||||
tm_out->tm_mon = month - 1; // tm_mon is 0-11
|
||||
tm_out->tm_year = year - 1900; // tm_year is years since 1900
|
||||
tm_out->tm_isdst = 0;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
@ -71,61 +83,110 @@ void gps_force_next_update(void) {
|
|||
ESP_LOGW(TAG, "Requesting forced GPS sync update");
|
||||
}
|
||||
|
||||
// Helper to convert struct tm to time_t (UTC assumption)
|
||||
// Uses standard mktime but we assume TZ is handled or default is UTC
|
||||
static time_t timegm_impl(struct tm *tm) {
|
||||
time_t t = mktime(tm);
|
||||
return t;
|
||||
}
|
||||
|
||||
static void gps_task(void* arg) {
|
||||
uint8_t d_buf[64];
|
||||
char line[128];
|
||||
int pos = 0;
|
||||
static int log_counter = 0;
|
||||
|
||||
// Ensure timezone is UTC for correct time math
|
||||
setenv("TZ", "UTC", 1);
|
||||
tzset();
|
||||
|
||||
while (1) {
|
||||
// Read from UART with a reasonable timeout
|
||||
int len = uart_read_bytes(gps_uart_num, d_buf, sizeof(d_buf), pdMS_TO_TICKS(100));
|
||||
|
||||
if (len > 0) {
|
||||
for (int i = 0; i < len; i++) {
|
||||
uint8_t data = d_buf[i];
|
||||
if (data == '\n') {
|
||||
line[pos] = '\0';
|
||||
struct tm gps_tm;
|
||||
bool valid;
|
||||
if (parse_gprmc(line, &gps_tm, &valid)) {
|
||||
if (valid) {
|
||||
time_t gps_time = mktime(&gps_tm);
|
||||
xSemaphoreTake(sync_mutex, portMAX_DELAY);
|
||||
next_pps_gps_second = gps_time + 1;
|
||||
xSemaphoreGive(sync_mutex);
|
||||
vTaskDelay(pdMS_TO_TICKS(300));
|
||||
xSemaphoreTake(sync_mutex, portMAX_DELAY);
|
||||
if (last_pps_monotonic > 0) {
|
||||
int64_t gps_us = (int64_t)next_pps_gps_second * 1000000LL;
|
||||
int64_t new_offset = gps_us - last_pps_monotonic;
|
||||
if (monotonic_offset_us == 0 || force_sync_update) {
|
||||
monotonic_offset_us = new_offset;
|
||||
if (force_sync_update) {
|
||||
ESP_LOGW(TAG, "GPS sync SNAP: Offset forced to %" PRIi64 " us", monotonic_offset_us);
|
||||
force_sync_update = false;
|
||||
log_counter = 0;
|
||||
|
||||
// Buffer the line
|
||||
if (data == '\n' || data == '\r') {
|
||||
if (pos > 0) {
|
||||
line[pos] = '\0';
|
||||
struct tm gps_tm;
|
||||
bool valid_fix;
|
||||
|
||||
// Try to parse GPRMC
|
||||
if (parse_gprmc(line, &gps_tm, &valid_fix)) {
|
||||
if (valid_fix) {
|
||||
// 1. Convert Parsed Time to Seconds
|
||||
time_t gps_time_sec = timegm_impl(&gps_tm);
|
||||
|
||||
// 2. Critical Section: Read PPS Timestamp
|
||||
xSemaphoreTake(sync_mutex, portMAX_DELAY);
|
||||
int64_t last_pps = last_pps_monotonic;
|
||||
xSemaphoreGive(sync_mutex);
|
||||
|
||||
// 3. Analyze Timing
|
||||
int64_t now = esp_timer_get_time();
|
||||
int64_t age_us = now - last_pps;
|
||||
|
||||
// The PPS pulse described by this message should have happened
|
||||
// fairly recently (e.g., within the last 800ms).
|
||||
// If age > 900ms, we likely missed the pulse or UART is lagging badly.
|
||||
if (last_pps > 0 && age_us < 900000) {
|
||||
|
||||
// Calculate Offset
|
||||
// GPS Time (in microseconds) = Seconds * 1M
|
||||
int64_t gps_time_us = (int64_t)gps_time_sec * 1000000LL;
|
||||
|
||||
// Offset = GPS_Timestamp - Monotonic_Timestamp
|
||||
// This means: GPS = Monotonic + Offset
|
||||
int64_t new_offset = gps_time_us - last_pps;
|
||||
|
||||
xSemaphoreTake(sync_mutex, portMAX_DELAY);
|
||||
if (monotonic_offset_us == 0 || force_sync_update) {
|
||||
// Hard Snap (First fix or Forced)
|
||||
monotonic_offset_us = new_offset;
|
||||
if (force_sync_update) {
|
||||
ESP_LOGW(TAG, "GPS SNAP: Offset forced to %" PRIi64 " us", monotonic_offset_us);
|
||||
force_sync_update = false;
|
||||
log_counter = 0; // Force immediate log
|
||||
}
|
||||
} else {
|
||||
// Exponential Smoothing (Filter Jitter)
|
||||
// 90% old, 10% new
|
||||
monotonic_offset_us = (monotonic_offset_us * 9 + new_offset) / 10;
|
||||
}
|
||||
gps_has_fix = true;
|
||||
xSemaphoreGive(sync_mutex);
|
||||
|
||||
// Periodic Logging
|
||||
if (log_counter <= 0) {
|
||||
ESP_LOGI(TAG, "GPS Sync: %02d:%02d:%02d | Offset: %" PRIi64 " us | PPS Age: %" PRIi64 " ms",
|
||||
gps_tm.tm_hour, gps_tm.tm_min, gps_tm.tm_sec,
|
||||
monotonic_offset_us, age_us / 1000);
|
||||
log_counter = 10; // Log every 10 valid fixes
|
||||
}
|
||||
log_counter--;
|
||||
|
||||
} else {
|
||||
monotonic_offset_us = (monotonic_offset_us * 9 + new_offset) / 10;
|
||||
// PPS signal lost or not correlated
|
||||
if (log_counter <= 0) {
|
||||
ESP_LOGW(TAG, "GPS valid but PPS missing/old (Age: %" PRIi64 " ms)", age_us / 1000);
|
||||
log_counter = 10;
|
||||
}
|
||||
log_counter--;
|
||||
}
|
||||
gps_has_fix = true;
|
||||
if (log_counter == 0) {
|
||||
ESP_LOGI(TAG, "GPS sync: %04d-%02d-%02d %02d:%02d:%02d, offset=%" PRIi64 " us",
|
||||
gps_tm.tm_year + 1900, gps_tm.tm_mon + 1, gps_tm.tm_mday,
|
||||
gps_tm.tm_hour, gps_tm.tm_min, gps_tm.tm_sec,
|
||||
monotonic_offset_us);
|
||||
log_counter = 60;
|
||||
}
|
||||
log_counter--;
|
||||
} else {
|
||||
gps_has_fix = false;
|
||||
}
|
||||
xSemaphoreGive(sync_mutex);
|
||||
} else {
|
||||
gps_has_fix = false;
|
||||
}
|
||||
}
|
||||
pos = 0;
|
||||
} else if (pos < sizeof(line) - 1) {
|
||||
line[pos++] = data;
|
||||
} else {
|
||||
if (pos < sizeof(line) - 1) {
|
||||
line[pos++] = data;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
@ -133,53 +194,48 @@ static void gps_task(void* arg) {
|
|||
}
|
||||
|
||||
void gps_sync_init(const gps_sync_config_t *config, bool use_gps_log_timestamps) {
|
||||
ESP_LOGI(TAG, "Checking for GPS PPS signal on GPIO %d...", config->pps_pin);
|
||||
ESP_LOGI(TAG, "Initializing GPS Sync (UART %d, PPS GPIO %d)", config->uart_port, config->pps_pin);
|
||||
|
||||
// 1. Configure PPS pin as Input to sense signal
|
||||
gpio_config_t pps_conf = {
|
||||
// 1. Initial PPS Pin Check (Input Mode)
|
||||
// We poll briefly just to see if the pin is physically toggling before committing resources.
|
||||
gpio_config_t pps_poll_conf = {
|
||||
.pin_bit_mask = (1ULL << config->pps_pin),
|
||||
.mode = GPIO_MODE_INPUT,
|
||||
.pull_up_en = GPIO_PULLUP_DISABLE,
|
||||
.pull_down_en = GPIO_PULLDOWN_DISABLE, // High-Z to detect active driving
|
||||
.pull_down_en = GPIO_PULLDOWN_DISABLE,
|
||||
.intr_type = GPIO_INTR_DISABLE
|
||||
};
|
||||
ESP_ERROR_CHECK(gpio_config(&pps_conf));
|
||||
ESP_ERROR_CHECK(gpio_config(&pps_poll_conf));
|
||||
|
||||
// 2. Poll for ~3 seconds to detect ANY edge transition
|
||||
bool pps_detected = false;
|
||||
int start_level = gpio_get_level(config->pps_pin);
|
||||
|
||||
// Poll loop: 3000 iterations * 1ms = 3 seconds
|
||||
for (int i = 0; i < 3000; i++) {
|
||||
int current_level = gpio_get_level(config->pps_pin);
|
||||
if (current_level != start_level) {
|
||||
// Poll for up to 2 seconds
|
||||
for (int i = 0; i < 2000; i++) {
|
||||
if (gpio_get_level(config->pps_pin) != start_level) {
|
||||
pps_detected = true;
|
||||
break; // Signal found!
|
||||
break;
|
||||
}
|
||||
vTaskDelay(pdMS_TO_TICKS(1));
|
||||
}
|
||||
|
||||
if (!pps_detected) {
|
||||
printf("GPS PPS not found over GPIO with pin number %d\n", config->pps_pin);
|
||||
ESP_LOGW(TAG, "GPS initialization aborted due to lack of PPS signal.");
|
||||
return; // ABORT INITIALIZATION
|
||||
ESP_LOGW(TAG, "No PPS signal detected on GPIO %d during boot check.", config->pps_pin);
|
||||
// We continue anyway, as GPS might gain lock later.
|
||||
} else {
|
||||
ESP_LOGI(TAG, "PPS signal activity detected.");
|
||||
}
|
||||
|
||||
ESP_LOGI(TAG, "PPS signal detected! Initializing GPS subsystem...");
|
||||
|
||||
// 3. Proceed with Full Initialization
|
||||
// 2. Setup Globals
|
||||
gps_uart_num = config->uart_port;
|
||||
use_gps_for_logs = use_gps_log_timestamps;
|
||||
|
||||
gps_force_next_update();
|
||||
sync_mutex = xSemaphoreCreateMutex();
|
||||
|
||||
if (use_gps_log_timestamps) {
|
||||
ESP_LOGI(TAG, "ESP_LOG timestamps: GPS time in seconds.milliseconds format");
|
||||
esp_log_set_vprintf(gps_log_vprintf);
|
||||
}
|
||||
|
||||
sync_mutex = xSemaphoreCreateMutex();
|
||||
|
||||
// 3. Setup UART
|
||||
uart_config_t uart_config = {
|
||||
.baud_rate = GPS_BAUD_RATE,
|
||||
.data_bits = UART_DATA_8_BITS,
|
||||
|
|
@ -191,49 +247,48 @@ void gps_sync_init(const gps_sync_config_t *config, bool use_gps_log_timestamps)
|
|||
|
||||
ESP_ERROR_CHECK(uart_driver_install(config->uart_port, UART_BUF_SIZE, 0, 0, NULL, 0));
|
||||
ESP_ERROR_CHECK(uart_param_config(config->uart_port, &uart_config));
|
||||
ESP_ERROR_CHECK(uart_set_pin(config->uart_port, config->tx_pin, config->rx_pin, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE));
|
||||
|
||||
ESP_ERROR_CHECK(uart_set_pin(config->uart_port,
|
||||
config->tx_pin,
|
||||
config->rx_pin,
|
||||
UART_PIN_NO_CHANGE,
|
||||
UART_PIN_NO_CHANGE));
|
||||
|
||||
// Re-configure PPS for Interrupts (Posedge)
|
||||
gpio_config_t io_conf = {
|
||||
// 4. Setup PPS Interrupt (Rising Edge)
|
||||
gpio_config_t pps_intr_conf = {
|
||||
.intr_type = GPIO_INTR_POSEDGE,
|
||||
.mode = GPIO_MODE_INPUT,
|
||||
.pin_bit_mask = (1ULL << config->pps_pin),
|
||||
.pull_up_en = GPIO_PULLUP_ENABLE,
|
||||
.pull_up_en = GPIO_PULLUP_DISABLE, // High-Z usually best for driven PPS
|
||||
.pull_down_en = GPIO_PULLDOWN_DISABLE,
|
||||
};
|
||||
ESP_ERROR_CHECK(gpio_config(&io_conf));
|
||||
ESP_ERROR_CHECK(gpio_config(&pps_intr_conf));
|
||||
|
||||
// Install ISR service if not already done by other components
|
||||
// Note: If you have other components using GPIO ISRs, ensure flags match or install is called only once.
|
||||
gpio_install_isr_service(0);
|
||||
ESP_ERROR_CHECK(gpio_isr_handler_add(config->pps_pin, pps_isr_handler, NULL));
|
||||
|
||||
// 5. Start Processor Task
|
||||
xTaskCreate(gps_task, "gps_task", 4096, NULL, 5, NULL);
|
||||
|
||||
ESP_LOGI(TAG, "GPS sync initialized (UART=%d, RX=%d, TX=%d, PPS=%d)",
|
||||
config->uart_port, config->rx_pin, config->tx_pin, config->pps_pin);
|
||||
}
|
||||
|
||||
gps_timestamp_t gps_get_timestamp(void) {
|
||||
gps_timestamp_t ts;
|
||||
// Capture raw monotonic time
|
||||
clock_gettime(CLOCK_MONOTONIC, &ts.mono_ts);
|
||||
xSemaphoreTake(sync_mutex, portMAX_DELAY);
|
||||
|
||||
// Calculate microseconds
|
||||
ts.monotonic_us = (int64_t)ts.mono_ts.tv_sec * 1000000LL + ts.mono_ts.tv_nsec / 1000;
|
||||
ts.monotonic_ms = ts.monotonic_us / 1000;
|
||||
|
||||
// Apply Offset safely
|
||||
xSemaphoreTake(sync_mutex, portMAX_DELAY);
|
||||
ts.gps_us = ts.monotonic_us + monotonic_offset_us;
|
||||
ts.gps_ms = ts.gps_us / 1000;
|
||||
ts.synced = gps_has_fix;
|
||||
xSemaphoreGive(sync_mutex);
|
||||
|
||||
ts.gps_ms = ts.gps_us / 1000;
|
||||
return ts;
|
||||
}
|
||||
|
||||
int64_t gps_get_monotonic_ms(void) {
|
||||
struct timespec ts;
|
||||
clock_gettime(CLOCK_MONOTONIC, &ts);
|
||||
return (int64_t)ts.tv_sec * 1000LL + ts.tv_nsec / 1000000;
|
||||
return esp_timer_get_time() / 1000;
|
||||
}
|
||||
|
||||
bool gps_is_synced(void) {
|
||||
|
|
@ -253,6 +308,7 @@ int gps_log_vprintf(const char *fmt, va_list args) {
|
|||
|
||||
if (use_gps_for_logs) {
|
||||
char *timestamp_start = NULL;
|
||||
// Find ESP log timestamp format "(1234)"
|
||||
for (int i = 0; buffer[i] != '\0' && i < sizeof(buffer) - 20; i++) {
|
||||
if ((buffer[i] == 'I' || buffer[i] == 'W' || buffer[i] == 'E' ||
|
||||
buffer[i] == 'D' || buffer[i] == 'V') &&
|
||||
|
|
@ -269,24 +325,35 @@ int gps_log_vprintf(const char *fmt, va_list args) {
|
|||
if (sscanf(timestamp_start, "%lu", &monotonic_log_ms) == 1) {
|
||||
char reformatted[512];
|
||||
size_t prefix_len = timestamp_start - buffer;
|
||||
|
||||
// Copy prefix "I "
|
||||
if (prefix_len > sizeof(reformatted)) prefix_len = sizeof(reformatted);
|
||||
memcpy(reformatted, buffer, prefix_len);
|
||||
|
||||
int decimal_len = 0;
|
||||
|
||||
if (gps_has_fix) {
|
||||
int64_t log_mono_us = (int64_t)monotonic_log_ms * 1000;
|
||||
int64_t log_gps_us = log_mono_us + monotonic_offset_us;
|
||||
|
||||
// Split into seconds and fractional ms
|
||||
uint64_t gps_sec = log_gps_us / 1000000;
|
||||
uint32_t gps_ms = (log_gps_us % 1000000) / 1000;
|
||||
|
||||
// Overwrite timestamp with GPS time e.g., "+1703000000.123"
|
||||
decimal_len = snprintf(reformatted + prefix_len,
|
||||
sizeof(reformatted) - prefix_len,
|
||||
"+%" PRIu64 ".%03lu", gps_sec, gps_ms);
|
||||
} else {
|
||||
// Fallback: Keep monotonic but mark as unsynced
|
||||
uint32_t sec = monotonic_log_ms / 1000;
|
||||
uint32_t ms = monotonic_log_ms % 1000;
|
||||
decimal_len = snprintf(reformatted + prefix_len,
|
||||
sizeof(reformatted) - prefix_len,
|
||||
"*%lu.%03lu", sec, ms);
|
||||
"*%lu.%03lu", (unsigned long)sec, (unsigned long)ms);
|
||||
}
|
||||
|
||||
// Copy remainder of message
|
||||
strcpy(reformatted + prefix_len + decimal_len, timestamp_end);
|
||||
return printf("%s", reformatted);
|
||||
}
|
||||
|
|
|
|||
|
|
@ -5,6 +5,8 @@
|
|||
#include "led_strip.h"
|
||||
#include "esp_log.h"
|
||||
|
||||
static const char *TAG = "status_led";
|
||||
|
||||
static led_strip_handle_t s_led_strip = NULL;
|
||||
static bool s_is_rgb = false;
|
||||
static int s_gpio_pin = -1;
|
||||
|
|
@ -15,6 +17,7 @@ static void set_color(uint8_t r, uint8_t g, uint8_t b) {
|
|||
led_strip_set_pixel(s_led_strip, 0, r, g, b);
|
||||
led_strip_refresh(s_led_strip);
|
||||
} else if (!s_is_rgb && s_gpio_pin >= 0) {
|
||||
// Simple LED: On if any color component is > 0
|
||||
gpio_set_level(s_gpio_pin, (r+g+b) > 0);
|
||||
}
|
||||
}
|
||||
|
|
@ -23,33 +26,40 @@ static void led_task(void *arg) {
|
|||
int toggle = 0;
|
||||
while (1) {
|
||||
switch (s_current_state) {
|
||||
case LED_STATE_NO_CONFIG: // Yellow
|
||||
if (s_is_rgb) { set_color(25, 25, 0); vTaskDelay(pdMS_TO_TICKS(1000)); }
|
||||
else { set_color(1,1,1); vTaskDelay(100); set_color(0,0,0); vTaskDelay(100); }
|
||||
case LED_STATE_NO_CONFIG: // Yellow (Solid for RGB, Blink for Single)
|
||||
if (s_is_rgb) { set_color(20, 20, 0); vTaskDelay(pdMS_TO_TICKS(1000)); }
|
||||
else { set_color(1,1,1); vTaskDelay(pdMS_TO_TICKS(100)); set_color(0,0,0); vTaskDelay(pdMS_TO_TICKS(100)); }
|
||||
break;
|
||||
case LED_STATE_WAITING: // Blue Blink
|
||||
set_color(0, 0, toggle ? 50 : 0); toggle = !toggle;
|
||||
case LED_STATE_WAITING: // Blue Blink (Searching)
|
||||
set_color(0, 0, toggle ? 50 : 0);
|
||||
toggle = !toggle;
|
||||
vTaskDelay(pdMS_TO_TICKS(500));
|
||||
break;
|
||||
case LED_STATE_CONNECTED: // Green Solid
|
||||
set_color(0, 25, 0); vTaskDelay(pdMS_TO_TICKS(1000));
|
||||
case LED_STATE_CONNECTED: // Green Solid (Idle)
|
||||
set_color(0, 20, 0);
|
||||
vTaskDelay(pdMS_TO_TICKS(1000));
|
||||
break;
|
||||
case LED_STATE_MONITORING: // Blue Solid
|
||||
set_color(0, 0, 50); vTaskDelay(pdMS_TO_TICKS(1000));
|
||||
case LED_STATE_MONITORING: // Blue Solid (Sniffer Mode)
|
||||
set_color(0, 0, 50);
|
||||
vTaskDelay(pdMS_TO_TICKS(1000));
|
||||
break;
|
||||
case LED_STATE_TRANSMITTING: // Fast Purple (Busy)
|
||||
set_color(toggle ? 50 : 0, 0, toggle ? 50 : 0); toggle = !toggle;
|
||||
case LED_STATE_TRANSMITTING: // Fast Purple Flash (Busy)
|
||||
set_color(toggle ? 50 : 0, 0, toggle ? 50 : 0);
|
||||
toggle = !toggle;
|
||||
vTaskDelay(pdMS_TO_TICKS(50));
|
||||
break;
|
||||
case LED_STATE_TRANSMITTING_SLOW: // Slow Purple (Relaxed)
|
||||
set_color(toggle ? 50 : 0, 0, toggle ? 50 : 0); toggle = !toggle;
|
||||
case LED_STATE_TRANSMITTING_SLOW: // Slow Purple Pulse (Pacing)
|
||||
set_color(toggle ? 50 : 0, 0, toggle ? 50 : 0);
|
||||
toggle = !toggle;
|
||||
vTaskDelay(pdMS_TO_TICKS(250));
|
||||
break;
|
||||
case LED_STATE_STALLED: // Purple Solid
|
||||
set_color(50, 0, 50); vTaskDelay(pdMS_TO_TICKS(1000));
|
||||
case LED_STATE_STALLED: // Purple Solid (Stalled)
|
||||
set_color(50, 0, 50);
|
||||
vTaskDelay(pdMS_TO_TICKS(1000));
|
||||
break;
|
||||
case LED_STATE_FAILED: // Red Blink
|
||||
set_color(toggle ? 50 : 0, 0, 0); toggle = !toggle;
|
||||
case LED_STATE_FAILED: // Red Blink (Error)
|
||||
set_color(toggle ? 50 : 0, 0, 0);
|
||||
toggle = !toggle;
|
||||
vTaskDelay(pdMS_TO_TICKS(200));
|
||||
break;
|
||||
}
|
||||
|
|
@ -59,15 +69,34 @@ static void led_task(void *arg) {
|
|||
void status_led_init(int gpio_pin, bool is_rgb_strip) {
|
||||
s_gpio_pin = gpio_pin;
|
||||
s_is_rgb = is_rgb_strip;
|
||||
|
||||
ESP_LOGI(TAG, "Initializing LED on GPIO %d (RGB=%d)", gpio_pin, is_rgb_strip);
|
||||
|
||||
if (s_is_rgb) {
|
||||
led_strip_config_t s_cfg = { .strip_gpio_num = gpio_pin, .max_leds = 1 };
|
||||
led_strip_rmt_config_t r_cfg = { .resolution_hz = 10 * 1000 * 1000 };
|
||||
led_strip_new_rmt_device(&s_cfg, &r_cfg, &s_led_strip);
|
||||
led_strip_config_t s_cfg = {
|
||||
.strip_gpio_num = gpio_pin,
|
||||
.max_leds = 1,
|
||||
.led_pixel_format = LED_PIXEL_FORMAT_GRB, // Standard for WS2812
|
||||
.led_model = LED_MODEL_WS2812, // Specific model
|
||||
.flags.invert_out = false,
|
||||
};
|
||||
led_strip_rmt_config_t r_cfg = {
|
||||
.resolution_hz = 10 * 1000 * 1000, // 10MHz
|
||||
.flags.with_dma = false,
|
||||
};
|
||||
|
||||
esp_err_t ret = led_strip_new_rmt_device(&s_cfg, &r_cfg, &s_led_strip);
|
||||
if (ret != ESP_OK) {
|
||||
ESP_LOGE(TAG, "Failed to create RMT LED strip: %s", esp_err_to_name(ret));
|
||||
return;
|
||||
}
|
||||
led_strip_clear(s_led_strip);
|
||||
} else {
|
||||
gpio_reset_pin(gpio_pin);
|
||||
gpio_set_direction(gpio_pin, GPIO_MODE_OUTPUT);
|
||||
gpio_set_level(gpio_pin, 0);
|
||||
}
|
||||
|
||||
xTaskCreate(led_task, "led_task", 2048, NULL, 5, NULL);
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -3,8 +3,9 @@
|
|||
#include "freertos/task.h"
|
||||
#include "esp_log.h"
|
||||
#include "esp_wifi.h"
|
||||
#include "esp_event.h" // Added
|
||||
#include "inttypes.h"
|
||||
#include "wifi_cfg.h" // Required for apply_from_nvs
|
||||
#include "wifi_cfg.h"
|
||||
|
||||
// Dependencies
|
||||
#include "iperf.h"
|
||||
|
|
@ -26,20 +27,24 @@ static bool s_monitor_enabled = false;
|
|||
static uint32_t s_monitor_frame_count = 0;
|
||||
static TaskHandle_t s_monitor_stats_task_handle = NULL;
|
||||
|
||||
// --- Helper: Log Collapse Events ---
|
||||
// --- Event Handler ---
|
||||
static void wifi_event_handler(void* arg, esp_event_base_t event_base, int32_t event_id, void* event_data) {
|
||||
if (event_base == IP_EVENT && event_id == IP_EVENT_STA_GOT_IP) {
|
||||
ESP_LOGI(TAG, "Got IP -> LED Connected");
|
||||
status_led_set_state(LED_STATE_CONNECTED);
|
||||
} else if (event_base == WIFI_EVENT && event_id == WIFI_EVENT_STA_DISCONNECTED) {
|
||||
status_led_set_state(LED_STATE_NO_CONFIG); // Or WAITING if retrying
|
||||
}
|
||||
}
|
||||
|
||||
// ... [Helper: Log Collapse Events (Same as before)] ...
|
||||
static void log_collapse_event(float nav_duration_us, int rssi, int retry) {
|
||||
gps_timestamp_t ts = gps_get_timestamp();
|
||||
printf("COLLAPSE,%" PRIi64 ",%" PRIi64 ",%d,%.2f,%d,%d\n",
|
||||
ts.monotonic_ms,
|
||||
ts.gps_ms,
|
||||
ts.synced ? 1 : 0,
|
||||
nav_duration_us,
|
||||
rssi,
|
||||
retry);
|
||||
ts.monotonic_ms, ts.gps_ms, ts.synced ? 1 : 0, nav_duration_us, rssi, retry);
|
||||
}
|
||||
|
||||
// --- Monitor Callbacks & Tasks ---
|
||||
|
||||
// ... [Monitor Callbacks (Same as before)] ...
|
||||
static void monitor_frame_callback(const wifi_frame_info_t *frame, const uint8_t *payload, uint16_t len) {
|
||||
s_monitor_frame_count++;
|
||||
if (frame->retry && frame->duration_id > 5000) {
|
||||
|
|
@ -57,10 +62,7 @@ static void monitor_stats_task(void *arg) {
|
|||
if (wifi_monitor_get_stats(&stats) == ESP_OK) {
|
||||
ESP_LOGI("MONITOR", "--- Stats: %lu frames, Retry: %.2f%%, Avg NAV: %u us ---",
|
||||
(unsigned long)stats.total_frames, stats.retry_rate, stats.avg_nav);
|
||||
|
||||
if (wifi_monitor_is_collapsed()) {
|
||||
ESP_LOGW("MONITOR", "⚠️ ⚠️ COLLAPSE DETECTED! ⚠️ ⚠️");
|
||||
}
|
||||
if (wifi_monitor_is_collapsed()) ESP_LOGW("MONITOR", "⚠️ ⚠️ COLLAPSE DETECTED! ⚠️ ⚠️");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
@ -85,14 +87,16 @@ void wifi_ctl_init(void) {
|
|||
s_monitor_enabled = false;
|
||||
s_monitor_frame_count = 0;
|
||||
|
||||
// -------------------------------------------------------------
|
||||
// CRITICAL FIX: Initialize the WiFi Driver via Config
|
||||
// This calls esp_wifi_init() and esp_wifi_start()
|
||||
// -------------------------------------------------------------
|
||||
// Register Event Handlers for LED feedback
|
||||
ESP_ERROR_CHECK(esp_event_handler_instance_register(IP_EVENT, IP_EVENT_STA_GOT_IP, &wifi_event_handler, NULL, NULL));
|
||||
ESP_ERROR_CHECK(esp_event_handler_instance_register(WIFI_EVENT, WIFI_EVENT_STA_DISCONNECTED, &wifi_event_handler, NULL, NULL));
|
||||
|
||||
if (!wifi_cfg_apply_from_nvs()) {
|
||||
ESP_LOGW(TAG, "No saved WiFi config found, driver initialized in defaults.");
|
||||
status_led_set_state(LED_STATE_NO_CONFIG);
|
||||
} else {
|
||||
ESP_LOGI(TAG, "WiFi driver initialized from NVS.");
|
||||
status_led_set_state(LED_STATE_WAITING); // Waiting for connection
|
||||
}
|
||||
|
||||
// Load Staging Params
|
||||
|
|
@ -102,11 +106,8 @@ void wifi_ctl_init(void) {
|
|||
}
|
||||
|
||||
// --- Parameter Management ---
|
||||
|
||||
void wifi_ctl_param_set_monitor_channel(uint8_t channel) {
|
||||
if (channel >= 1 && channel <= 14) {
|
||||
s_monitor_channel_staging = channel;
|
||||
}
|
||||
if (channel >= 1 && channel <= 14) s_monitor_channel_staging = channel;
|
||||
}
|
||||
|
||||
uint8_t wifi_ctl_param_get_monitor_channel(void) {
|
||||
|
|
@ -115,9 +116,7 @@ uint8_t wifi_ctl_param_get_monitor_channel(void) {
|
|||
|
||||
bool wifi_ctl_param_save(void) {
|
||||
bool changed = wifi_cfg_set_monitor_channel(s_monitor_channel_staging);
|
||||
if (changed) {
|
||||
ESP_LOGI(TAG, "Monitor channel (%d) saved to NVS", s_monitor_channel_staging);
|
||||
}
|
||||
if (changed) ESP_LOGI(TAG, "Monitor channel (%d) saved to NVS", s_monitor_channel_staging);
|
||||
return changed;
|
||||
}
|
||||
|
||||
|
|
@ -129,6 +128,16 @@ void wifi_ctl_param_reload(void) {
|
|||
ESP_LOGI(TAG, "Reloaded monitor channel: %d", s_monitor_channel_staging);
|
||||
}
|
||||
|
||||
void wifi_ctl_param_clear(void) {
|
||||
// 1. Erase NVS
|
||||
wifi_cfg_clear_monitor_channel();
|
||||
|
||||
// 2. Reset RAM Staging to Default (6)
|
||||
s_monitor_channel_staging = 6;
|
||||
|
||||
ESP_LOGI(TAG, "Monitor configuration cleared (Defaulting to Ch 6).");
|
||||
}
|
||||
|
||||
bool wifi_ctl_param_is_unsaved(void) {
|
||||
return wifi_cfg_monitor_channel_is_unsaved(s_monitor_channel_staging);
|
||||
}
|
||||
|
|
@ -224,16 +233,6 @@ esp_err_t wifi_ctl_switch_to_sta(wifi_band_mode_t band_mode) {
|
|||
return ESP_OK;
|
||||
}
|
||||
|
||||
void wifi_ctl_param_clear(void) {
|
||||
// 1. Erase NVS
|
||||
wifi_cfg_clear_monitor_channel();
|
||||
|
||||
// 2. Reset RAM Staging to Default (6)
|
||||
s_monitor_channel_staging = 6;
|
||||
|
||||
ESP_LOGI(TAG, "Monitor configuration cleared (Defaulting to Ch 6).");
|
||||
}
|
||||
|
||||
void wifi_ctl_auto_monitor_start(uint8_t channel) {
|
||||
xTaskCreate(auto_monitor_task_func, "auto_monitor", 4096, (void*)(uintptr_t)channel, 5, NULL);
|
||||
}
|
||||
|
|
|
|||
|
|
@ -2,7 +2,7 @@
|
|||
|
||||
#include "esp_err.h"
|
||||
#include "esp_wifi.h"
|
||||
#include <stdbool.h> // Added
|
||||
#include <stdbool.h>
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
|
|
@ -15,17 +15,15 @@ typedef enum {
|
|||
|
||||
void wifi_ctl_init(void);
|
||||
|
||||
void wifi_ctl_param_clear(void);
|
||||
|
||||
// --- Parameter Management (Set/Get/Save/Read) ---
|
||||
// --- Parameter Management ---
|
||||
void wifi_ctl_param_set_monitor_channel(uint8_t channel);
|
||||
uint8_t wifi_ctl_param_get_monitor_channel(void);
|
||||
bool wifi_ctl_param_save(void); // Returns true if NVS updated
|
||||
bool wifi_ctl_param_save(void);
|
||||
void wifi_ctl_param_reload(void);
|
||||
bool wifi_ctl_param_is_unsaved(void); // Dirty Check
|
||||
bool wifi_ctl_param_is_unsaved(void);
|
||||
void wifi_ctl_param_clear(void);
|
||||
|
||||
// --- Actions ---
|
||||
// Update: channel_override=0 uses Staged config
|
||||
esp_err_t wifi_ctl_switch_to_monitor(uint8_t channel_override, wifi_bandwidth_t bandwidth);
|
||||
esp_err_t wifi_ctl_switch_to_sta(wifi_band_mode_t band_mode);
|
||||
void wifi_ctl_auto_monitor_start(uint8_t channel);
|
||||
|
|
|
|||
|
|
@ -2,44 +2,47 @@
|
|||
#define BOARD_CONFIG_H
|
||||
|
||||
#include "sdkconfig.h"
|
||||
#include "driver/gpio.h"
|
||||
|
||||
|
||||
#if defined (CONFIG_IDF_TARGET_ESP32C5)
|
||||
// ============================================================================
|
||||
// ESP32-C5 (DevKitC-1)
|
||||
// ESP32-C5 (DevKitC-1) 3.3V VCC Pin 1 GND PIN 15
|
||||
// ============================================================================
|
||||
#ifdef CONFIG_IDF_TARGET_ESP32C5
|
||||
#define RGB_LED_GPIO 8 // Common addressable LED pin for C5
|
||||
#define HAS_RGB_LED 1
|
||||
#endif
|
||||
|
||||
#define GPS_TX_PIN GPIO_NUM_24
|
||||
#define GPS_RX_PIN GPIO_NUM_23
|
||||
#define GPS_PPS_PIN GPIO_NUM_25
|
||||
#elif defined (CONFIG_IDF_TARGET_ESP32S3)
|
||||
// ============================================================================
|
||||
// ESP32-S3 (DevKitC-1)
|
||||
// Most S3 DevKits use GPIO 48 for the addressable RGB LED.
|
||||
// If yours uses GPIO 38, change this value.
|
||||
// ============================================================================
|
||||
#ifdef CONFIG_IDF_TARGET_ESP32S3
|
||||
// Most S3 DevKits use GPIO 48 for the addressable RGB LED.
|
||||
// If yours uses GPIO 38, change this value.
|
||||
#define RGB_LED_GPIO 48
|
||||
#define HAS_RGB_LED 1
|
||||
#endif
|
||||
|
||||
#define RGB_LED_GPIO 48
|
||||
#define HAS_RGB_LED 1
|
||||
#define GPS_TX_PIN GPIO_NUM_5
|
||||
#define GPS_RX_PIN GPIO_NUM_4
|
||||
#define GPS_PPS_PIN GPIO_NUM_6
|
||||
#elif defined (CONFIG_IDF_TARGET_ESP32)
|
||||
// ============================================================================
|
||||
// ESP32 (Original / Standard)
|
||||
// Standard ESP32 DevKits usually have a single blue LED on GPIO 2.
|
||||
// They rarely have an addressable RGB LED built-in.
|
||||
// ============================================================================
|
||||
#ifdef CONFIG_IDF_TARGET_ESP32
|
||||
// Standard ESP32 DevKits usually have a single blue LED on GPIO 2.
|
||||
// They rarely have an addressable RGB LED built-in.
|
||||
#define RGB_LED_GPIO 2
|
||||
#define HAS_RGB_LED 0
|
||||
#endif
|
||||
|
||||
// ============================================================================
|
||||
// Fallbacks (Prevent Compilation Errors)
|
||||
// ============================================================================
|
||||
#ifndef RGB_LED_GPIO
|
||||
#define RGB_LED_GPIO 2
|
||||
#endif
|
||||
|
||||
#ifndef HAS_RGB_LED
|
||||
#define HAS_RGB_LED 0
|
||||
#define RGB_LED_GPIO 2 // Standard Blue LED
|
||||
#define HAS_RGB_LED 0 // Not RGB
|
||||
#define GPS_TX_PIN GPIO_NUM_17
|
||||
#define GPS_RX_PIN GPIO_NUM_16
|
||||
#define GPS_PPS_PIN GPIO_NUM_4
|
||||
#else
|
||||
// Fallback
|
||||
#define RGB_LED_GPIO 8
|
||||
#define HAS_RGB_LED 1
|
||||
#define GPS_TX_PIN GPIO_NUM_1
|
||||
#define GPS_RX_PIN GPIO_NUM_3
|
||||
#define GPS_PPS_PIN GPIO_NUM_5
|
||||
#endif
|
||||
|
||||
#endif // BOARD_CONFIG_H
|
||||
|
|
|
|||
|
|
@ -15,6 +15,7 @@
|
|||
// Components
|
||||
#include "status_led.h"
|
||||
#include "board_config.h"
|
||||
#include "gps_sync.h"
|
||||
#include "wifi_controller.h"
|
||||
#include "wifi_cfg.h"
|
||||
#include "app_console.h"
|
||||
|
|
@ -92,6 +93,13 @@ void app_main(void) {
|
|||
// 2. Initialize Netif & Event Loop
|
||||
ESP_ERROR_CHECK(esp_netif_init());
|
||||
ESP_ERROR_CHECK(esp_event_loop_create_default());
|
||||
const gps_sync_config_t gps_cfg = {
|
||||
.uart_port = UART_NUM_1,
|
||||
.tx_pin = GPS_TX_PIN,
|
||||
.rx_pin = GPS_RX_PIN,
|
||||
.pps_pin = GPS_PPS_PIN,
|
||||
};
|
||||
gps_sync_init(&gps_cfg, true);
|
||||
|
||||
// 3. Hardware Init
|
||||
status_led_init(RGB_LED_GPIO, HAS_RGB_LED);
|
||||
|
|
|
|||
Loading…
Reference in New Issue