Upload files to "/"
This commit is contained in:
282
HARDWARE_TEST.md
Normal file
282
HARDWARE_TEST.md
Normal file
@@ -0,0 +1,282 @@
|
|||||||
|
# ESP32-S3 CAN FD Logger - Hardware Test Checklist
|
||||||
|
|
||||||
|
## Pre-Test Checklist
|
||||||
|
|
||||||
|
### 1. Hardware Connections
|
||||||
|
- [ ] ESP32-S3-WROOM-1-N16R8 properly seated
|
||||||
|
- [ ] MCP2518FD CAN FD Controller connected via HSPI
|
||||||
|
- [ ] MISO (GPIO13)
|
||||||
|
- [ ] MOSI (GPIO11)
|
||||||
|
- [ ] SCLK (GPIO12)
|
||||||
|
- [ ] CS (GPIO10)
|
||||||
|
- [ ] INT (GPIO3)
|
||||||
|
- [ ] STBY connected to GND
|
||||||
|
- [ ] SD Card connected via SDIO 4-bit mode
|
||||||
|
- [ ] CLK (GPIO39)
|
||||||
|
- [ ] CMD (GPIO38)
|
||||||
|
- [ ] D0 (GPIO40)
|
||||||
|
- [ ] D1 (GPIO41)
|
||||||
|
- [ ] D2 (GPIO42)
|
||||||
|
- [ ] D3 (GPIO21)
|
||||||
|
- [ ] DS3231 RTC connected via I2C
|
||||||
|
- [ ] SDA (GPIO8)
|
||||||
|
- [ ] SCL (GPIO9)
|
||||||
|
- [ ] CAN Bus termination (120Ω) at both ends
|
||||||
|
- [ ] Power supply stable (5V, sufficient current)
|
||||||
|
|
||||||
|
### 2. Arduino IDE Settings
|
||||||
|
```
|
||||||
|
Board: ESP32S3 Dev Module
|
||||||
|
USB CDC On Boot: Enabled
|
||||||
|
CPU Frequency: 240MHz
|
||||||
|
Flash Mode: QIO 80MHz
|
||||||
|
Flash Size: 16MB (128Mb)
|
||||||
|
Partition Scheme: 16M Flash (3MB APP/9.9MB FAT)
|
||||||
|
PSRAM: OPI PSRAM
|
||||||
|
Upload Speed: 921600
|
||||||
|
```
|
||||||
|
|
||||||
|
### 3. Required Libraries
|
||||||
|
- [ ] ACAN2517FD (Pierre Molinaro) - v1.1.0+
|
||||||
|
- [ ] RTClib (Adafruit)
|
||||||
|
- [ ] ArduinoJson - v6.x
|
||||||
|
- [ ] WebSocketsServer (Links2004)
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
## Test Procedures
|
||||||
|
|
||||||
|
### Test 1: Basic Power-On Test
|
||||||
|
|
||||||
|
1. Connect USB-C cable
|
||||||
|
2. Open Serial Monitor (115200 baud)
|
||||||
|
3. Verify boot messages:
|
||||||
|
```
|
||||||
|
================================
|
||||||
|
ESP32-S3 CAN FD Logger
|
||||||
|
Version 2.0 - PSRAM Optimized
|
||||||
|
================================
|
||||||
|
PSRAM found: 8 MB
|
||||||
|
[PSRAM] Allocated XXXXX bytes for XXXX frames
|
||||||
|
SD Card mounted successfully!
|
||||||
|
CAN FD initialized successfully!
|
||||||
|
System ready!
|
||||||
|
```
|
||||||
|
|
||||||
|
**Pass Criteria**: All initialization messages appear without errors
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
### Test 2: WiFi AP Mode Test
|
||||||
|
|
||||||
|
1. After boot, check WiFi networks on phone/PC
|
||||||
|
2. Connect to `ESP32-CANLogger` (open, no password)
|
||||||
|
3. Open browser: `http://192.168.4.1`
|
||||||
|
4. Verify dashboard loads
|
||||||
|
|
||||||
|
**Pass Criteria**:
|
||||||
|
- AP visible in WiFi list
|
||||||
|
- Connection successful
|
||||||
|
- Web page loads
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
### Test 3: CAN FD Loopback Test
|
||||||
|
|
||||||
|
1. Navigate to `/test` page
|
||||||
|
2. Set Frame Count: 1000
|
||||||
|
3. Set Interval: 1000μs
|
||||||
|
4. Click "Start Loopback Test"
|
||||||
|
5. Wait for completion
|
||||||
|
|
||||||
|
**Pass Criteria**:
|
||||||
|
- Frames Sent = Frames Received
|
||||||
|
- Frames Lost = 0
|
||||||
|
- Loss Rate = 0%
|
||||||
|
- Result = PASS
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
### Test 4: CAN FD Stress Test
|
||||||
|
|
||||||
|
1. Navigate to `/test` page
|
||||||
|
2. Set Frame Count: 5000
|
||||||
|
3. Set Data Length: 64 bytes
|
||||||
|
4. Set CAN FD Mode: CAN FD
|
||||||
|
5. Click "Start Stress Test"
|
||||||
|
|
||||||
|
**Pass Criteria**:
|
||||||
|
- Frame Rate > 1000 fps
|
||||||
|
- Loss Rate < 0.1%
|
||||||
|
- Result = PASS
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
### Test 5: SD Card Logging Test
|
||||||
|
|
||||||
|
1. Navigate to dashboard (`/`)
|
||||||
|
2. Click "Start Logging"
|
||||||
|
3. Generate CAN traffic (use CAN FD TX or external source)
|
||||||
|
4. Wait 10+ seconds
|
||||||
|
5. Click "Stop Logging"
|
||||||
|
6. Navigate to `/files`
|
||||||
|
7. Download the .pcap file
|
||||||
|
8. Open in Wireshark
|
||||||
|
|
||||||
|
**Pass Criteria**:
|
||||||
|
- Log file created
|
||||||
|
- File size > 0
|
||||||
|
- Wireshark can parse file
|
||||||
|
- Frames have correct timestamps
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
### Test 6: Real-time Graph Test
|
||||||
|
|
||||||
|
1. Navigate to `/graph`
|
||||||
|
2. If no signals defined:
|
||||||
|
- Go to `/settings`
|
||||||
|
- Add manual signal: ID=0x100, StartBit=0, Length=16
|
||||||
|
3. Generate CAN traffic with ID 0x100
|
||||||
|
4. Verify graph updates
|
||||||
|
|
||||||
|
**Pass Criteria**:
|
||||||
|
- Signal appears in list
|
||||||
|
- Graph shows data
|
||||||
|
- Updates in real-time (< 500ms latency)
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
### Test 7: DS3231 RTC Test
|
||||||
|
|
||||||
|
1. Navigate to `/settings`
|
||||||
|
2. Click "Sync Time from Device"
|
||||||
|
3. Verify current time updates
|
||||||
|
4. Power cycle device
|
||||||
|
5. Check time is preserved
|
||||||
|
|
||||||
|
**Pass Criteria**:
|
||||||
|
- Time sync successful
|
||||||
|
- Time preserved after power cycle
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
### Test 8: CAN FD External Communication Test
|
||||||
|
|
||||||
|
**Prerequisites**: External CAN FD device or analyzer
|
||||||
|
|
||||||
|
1. Connect CAN H/L to external device
|
||||||
|
2. Set CAN mode to Normal (not Loopback)
|
||||||
|
3. Set baudrate to match external device
|
||||||
|
4. Send frames from external device
|
||||||
|
5. Verify frames appear in log
|
||||||
|
6. Send frames from ESP32
|
||||||
|
7. Verify frames received on external device
|
||||||
|
|
||||||
|
**Pass Criteria**:
|
||||||
|
- Bidirectional communication works
|
||||||
|
- No frame corruption
|
||||||
|
- Timing within expected range
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
### Test 9: Memory Stress Test
|
||||||
|
|
||||||
|
1. Navigate to `/api/memory`
|
||||||
|
2. Record initial memory values
|
||||||
|
3. Run stress test (10,000 frames)
|
||||||
|
4. Check memory again
|
||||||
|
5. Run for extended period (5+ minutes)
|
||||||
|
|
||||||
|
**Pass Criteria**:
|
||||||
|
- No memory leaks (free memory stable)
|
||||||
|
- PSRAM usage reasonable
|
||||||
|
- System doesn't crash
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
### Test 10: WiFi Stability Test
|
||||||
|
|
||||||
|
1. Connect to AP
|
||||||
|
2. Open 3 browser tabs with different pages
|
||||||
|
3. Run loopback test
|
||||||
|
4. Keep websockets connected
|
||||||
|
5. Monitor for 5+ minutes
|
||||||
|
|
||||||
|
**Pass Criteria**:
|
||||||
|
- No disconnections
|
||||||
|
- All pages responsive
|
||||||
|
- WebSocket still connected
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
## Performance Benchmarks
|
||||||
|
|
||||||
|
### Expected Performance (ESP32-S3 @ 240MHz)
|
||||||
|
|
||||||
|
| Metric | Target | Notes |
|
||||||
|
|--------|--------|-------|
|
||||||
|
| CAN FD RX Rate | > 5000 fps | With logging |
|
||||||
|
| CAN FD TX Rate | > 3000 fps | No logging |
|
||||||
|
| SD Write Speed | > 1 MB/s | SDIO 4-bit |
|
||||||
|
| WebSocket Latency | < 200 ms | 10 signals |
|
||||||
|
| PSRAM Buffer | 6000+ frames | Overflow protection |
|
||||||
|
| Heap Available | > 100 KB | During operation |
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
## Troubleshooting
|
||||||
|
|
||||||
|
### CAN FD Not Initializing
|
||||||
|
- Check SPI connections
|
||||||
|
- Verify crystal oscillator (40MHz)
|
||||||
|
- Check CS and INT pins
|
||||||
|
- Verify MCP2518FD power supply
|
||||||
|
|
||||||
|
### SD Card Mount Failed
|
||||||
|
- Check SDIO connections
|
||||||
|
- Try different SD card
|
||||||
|
- Verify card is FAT32 formatted
|
||||||
|
- Check card speed class (Class 10 recommended)
|
||||||
|
|
||||||
|
### WiFi Not Connecting
|
||||||
|
- Check antenna (if external)
|
||||||
|
- Verify no 2.4GHz interference
|
||||||
|
- Check power supply (WiFi requires peak current)
|
||||||
|
|
||||||
|
### Frame Loss Detected
|
||||||
|
- Check CAN bus termination
|
||||||
|
- Verify baudrate match
|
||||||
|
- Check for bus errors
|
||||||
|
- Monitor CPU load via `/api/memory`
|
||||||
|
|
||||||
|
### Memory Leaks
|
||||||
|
- Check for proper task stack sizes
|
||||||
|
- Verify PSRAM allocation
|
||||||
|
- Monitor heap over time
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
## Test Log Template
|
||||||
|
|
||||||
|
```
|
||||||
|
Date: ________________
|
||||||
|
Tester: ________________
|
||||||
|
Hardware Version: ________________
|
||||||
|
Firmware Version: ________________
|
||||||
|
|
||||||
|
Test 1: Power-On [ ] PASS [ ] FAIL Notes: ________________
|
||||||
|
Test 2: WiFi AP [ ] PASS [ ] FAIL Notes: ________________
|
||||||
|
Test 3: Loopback [ ] PASS [ ] FAIL Notes: ________________
|
||||||
|
Test 4: Stress [ ] PASS [ ] FAIL Notes: ________________
|
||||||
|
Test 5: SD Logging [ ] PASS [ ] FAIL Notes: ________________
|
||||||
|
Test 6: Graph [ ] PASS [ ] FAIL Notes: ________________
|
||||||
|
Test 7: RTC [ ] PASS [ ] FAIL Notes: ________________
|
||||||
|
Test 8: External CAN [ ] PASS [ ] FAIL Notes: ________________
|
||||||
|
Test 9: Memory [ ] PASS [ ] FAIL Notes: ________________
|
||||||
|
Test 10: WiFi Stable [ ] PASS [ ] FAIL Notes: ________________
|
||||||
|
|
||||||
|
Overall Result: [ ] PASS [ ] FAIL
|
||||||
|
|
||||||
|
Signature: ________________
|
||||||
|
```
|
||||||
121
PIN_VALIDATION.md
Normal file
121
PIN_VALIDATION.md
Normal file
@@ -0,0 +1,121 @@
|
|||||||
|
# ESP32-S3 CAN FD Logger - Pin Validation
|
||||||
|
|
||||||
|
## Hardware Configuration Overview
|
||||||
|
|
||||||
|
**Board**: ESP32-S3-WROOM-1-N16R8
|
||||||
|
- Flash: 16MB Quad SPI
|
||||||
|
- PSRAM: 8MB Octal SPI (uses GPIO33-37)
|
||||||
|
- Cores: Dual Xtensa LX7 @ 240MHz
|
||||||
|
|
||||||
|
## Pin Assignment Analysis
|
||||||
|
|
||||||
|
### HSPI (CAN FD MCP2518FD)
|
||||||
|
| Pin | GPIO | Function | Status | Notes |
|
||||||
|
|-----|------|----------|--------|-------|
|
||||||
|
| MISO | GPIO13 | SPI Data In | ✅ OK | - |
|
||||||
|
| MOSI | GPIO11 | SPI Data Out | ✅ OK | - |
|
||||||
|
| SCLK | GPIO12 | SPI Clock | ✅ OK | - |
|
||||||
|
| CS | GPIO10 | Chip Select | ✅ OK | - |
|
||||||
|
| INT | GPIO3 | Interrupt | ⚠️ OK | No USB conflict (USB not used) |
|
||||||
|
|
||||||
|
### SDIO 4-bit (SD Card)
|
||||||
|
| Pin | GPIO | Function | Status | Notes |
|
||||||
|
|-----|------|----------|--------|-------|
|
||||||
|
| CLK | GPIO39 | SDIO Clock | ✅ OK | - |
|
||||||
|
| CMD | GPIO38 | SDIO Command | ✅ OK | - |
|
||||||
|
| D0 | GPIO40 | SDIO Data 0 | ✅ OK | - |
|
||||||
|
| D1 | GPIO41 | SDIO Data 1 | ✅ OK | - |
|
||||||
|
| D2 | GPIO42 | SDIO Data 2 | ✅ OK | - |
|
||||||
|
| D3 | GPIO21 | SDIO Data 3 | ⚠️ WARNING | Strapping pin (see below) |
|
||||||
|
|
||||||
|
### I2C (DS3231 RTC)
|
||||||
|
| Pin | GPIO | Function | Status | Notes |
|
||||||
|
|-----|------|----------|--------|-------|
|
||||||
|
| SDA | GPIO8 | I2C Data | ✅ OK | - |
|
||||||
|
| SCL | GPIO9 | I2C Clock | ✅ OK | - |
|
||||||
|
|
||||||
|
## Critical Pin Analysis
|
||||||
|
|
||||||
|
### 1. PSRAM Conflict Check ✅
|
||||||
|
**PSRAM uses**: GPIO33, 34, 35, 36, 37
|
||||||
|
|
||||||
|
**Our pins**: GPIO3, 8, 9, 10, 11, 12, 13, 21, 38, 39, 40, 41, 42
|
||||||
|
|
||||||
|
**Result**: NO CONFLICT
|
||||||
|
- All our pins are outside the PSRAM range (33-37)
|
||||||
|
- SDIO pins (38-42, 21) are safe to use
|
||||||
|
|
||||||
|
### 2. GPIO21 (Strapping Pin) ⚠️
|
||||||
|
GPIO21 is a **strapping pin** used during boot:
|
||||||
|
- Internal pull-up resistor (~10kΩ)
|
||||||
|
- Used for boot mode selection
|
||||||
|
- Safe to use after boot initialization
|
||||||
|
|
||||||
|
**Recommendation**:
|
||||||
|
- SDIO_D3 (GPIO21) will work correctly
|
||||||
|
- Pull-down resistor is already present in strapping logic
|
||||||
|
- No additional hardware changes needed
|
||||||
|
|
||||||
|
### 3. GPIO3 (INT Pin) ⚠️
|
||||||
|
GPIO3 is USB D- in USB mode:
|
||||||
|
- User confirmed: **USB NOT USED**
|
||||||
|
- USB CDC is used via Native USB (GPIO19/20)
|
||||||
|
- Safe to use GPIO3 for CAN interrupt
|
||||||
|
|
||||||
|
## Arduino IDE Configuration
|
||||||
|
|
||||||
|
### Board Settings
|
||||||
|
```
|
||||||
|
Board: ESP32S3 Dev Module
|
||||||
|
USB CDC On Boot: Enabled
|
||||||
|
CPU Frequency: 240MHz
|
||||||
|
Flash Mode: QIO 80MHz
|
||||||
|
Flash Size: 16MB (128Mb)
|
||||||
|
Partition Scheme: 16M Flash (3MB APP/9.9MB FAT)
|
||||||
|
PSRAM: OPI PSRAM
|
||||||
|
Upload Mode: UART0 / Hardware CDC
|
||||||
|
Upload Speed: 921600
|
||||||
|
```
|
||||||
|
|
||||||
|
### Why These Settings?
|
||||||
|
- **USB CDC On Boot**: Required for Serial.println() to work over USB
|
||||||
|
- **Partition Scheme 16M**: Maximizes available flash for app and SPIFFS
|
||||||
|
- **PSRAM OPI**: Required for 8MB Octal PSRAM operation
|
||||||
|
- **Upload Mode UART0**: Standard serial upload via USB
|
||||||
|
|
||||||
|
## Pin Mapping Reference
|
||||||
|
|
||||||
|
```
|
||||||
|
GPIO Function Status
|
||||||
|
---- -------- ------
|
||||||
|
3 CAN_INT OK (USB unused)
|
||||||
|
8 RTC_SDA OK
|
||||||
|
9 RTC_SCL OK
|
||||||
|
10 HSPI_CS OK
|
||||||
|
11 HSPI_MOSI OK
|
||||||
|
12 HSPI_SCLK OK
|
||||||
|
13 HSPI_MISO OK
|
||||||
|
21 SDIO_D3 OK (Strapping pin)
|
||||||
|
38 SDIO_CMD OK
|
||||||
|
39 SDIO_CLK OK
|
||||||
|
40 SDIO_D0 OK
|
||||||
|
41 SDIO_D1 OK
|
||||||
|
42 SDIO_D2 OK
|
||||||
|
|
||||||
|
PSRAM Pins (DO NOT USE):
|
||||||
|
33-37 Reserved for Octal PSRAM
|
||||||
|
```
|
||||||
|
|
||||||
|
## Summary
|
||||||
|
|
||||||
|
✅ **All pins validated successfully**
|
||||||
|
- No PSRAM conflicts
|
||||||
|
- SDIO 4-bit mode pins are available
|
||||||
|
- CAN FD interrupt pin is safe (USB not used)
|
||||||
|
- RTC I2C pins are standard and available
|
||||||
|
|
||||||
|
⚠️ **Warnings (non-critical)**
|
||||||
|
- GPIO21 is strapping pin but safe for SDIO after boot
|
||||||
|
- GPIO3 would conflict with USB if USB Serial was used
|
||||||
|
|
||||||
|
**Hardware is ready for implementation.**
|
||||||
181
auto_trigger.cpp
Normal file
181
auto_trigger.cpp
Normal file
@@ -0,0 +1,181 @@
|
|||||||
|
// auto_trigger.cpp - Auto-Logging Trigger Implementation
|
||||||
|
|
||||||
|
#include "auto_trigger.h"
|
||||||
|
|
||||||
|
TriggerConfig triggerConfig;
|
||||||
|
bool triggerActive = false;
|
||||||
|
bool loggingActive = false;
|
||||||
|
static uint32_t loggingStartTime = 0;
|
||||||
|
|
||||||
|
void initAutoTrigger() {
|
||||||
|
triggerConfig.conditionCount = 0;
|
||||||
|
triggerConfig.logicOp = LOGIC_AND;
|
||||||
|
triggerConfig.enabled = false;
|
||||||
|
triggerConfig.autoStart = true;
|
||||||
|
triggerConfig.autoStop = false;
|
||||||
|
triggerConfig.durationMs = 0;
|
||||||
|
triggerActive = false;
|
||||||
|
loggingActive = false;
|
||||||
|
|
||||||
|
loadTriggerConfig();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool addTriggerCondition(const char* signalName, TriggerOperator op, float threshold) {
|
||||||
|
if (triggerConfig.conditionCount >= MAX_TRIGGER_CONDITIONS) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
TriggerCondition* cond = &triggerConfig.conditions[triggerConfig.conditionCount++];
|
||||||
|
strncpy(cond->signalName, signalName, 31);
|
||||||
|
cond->op = op;
|
||||||
|
cond->threshold = threshold;
|
||||||
|
cond->active = true;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool removeTriggerCondition(uint8_t index) {
|
||||||
|
if (index >= triggerConfig.conditionCount) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Shift conditions
|
||||||
|
for (uint8_t i = index; i < triggerConfig.conditionCount - 1; i++) {
|
||||||
|
triggerConfig.conditions[i] = triggerConfig.conditions[i + 1];
|
||||||
|
}
|
||||||
|
triggerConfig.conditionCount--;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void clearTriggerConditions() {
|
||||||
|
triggerConfig.conditionCount = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void setLogicalOperator(LogicalOperator op) {
|
||||||
|
triggerConfig.logicOp = op;
|
||||||
|
}
|
||||||
|
|
||||||
|
void enableTrigger(bool enable) {
|
||||||
|
triggerConfig.enabled = enable;
|
||||||
|
if (!enable) {
|
||||||
|
triggerActive = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void setAutoStart(bool enable) {
|
||||||
|
triggerConfig.autoStart = enable;
|
||||||
|
}
|
||||||
|
|
||||||
|
void setAutoStop(bool enable) {
|
||||||
|
triggerConfig.autoStop = enable;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool checkTriggerConditions() {
|
||||||
|
if (triggerConfig.conditionCount == 0) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool result = (triggerConfig.logicOp == LOGIC_AND);
|
||||||
|
|
||||||
|
for (uint8_t i = 0; i < triggerConfig.conditionCount; i++) {
|
||||||
|
TriggerCondition* cond = &triggerConfig.conditions[i];
|
||||||
|
if (!cond->active) continue;
|
||||||
|
|
||||||
|
// Get current signal value
|
||||||
|
SignalValue* sv = getSignalValue(cond->signalName);
|
||||||
|
if (!sv || !sv->valid) {
|
||||||
|
if (triggerConfig.logicOp == LOGIC_AND) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool conditionMet = false;
|
||||||
|
switch (cond->op) {
|
||||||
|
case TRIGGER_OP_GREATER:
|
||||||
|
conditionMet = sv->value > cond->threshold;
|
||||||
|
break;
|
||||||
|
case TRIGGER_OP_LESS:
|
||||||
|
conditionMet = sv->value < cond->threshold;
|
||||||
|
break;
|
||||||
|
case TRIGGER_OP_EQUAL:
|
||||||
|
conditionMet = fabs(sv->value - cond->threshold) < 0.001;
|
||||||
|
break;
|
||||||
|
case TRIGGER_OP_GREATER_EQ:
|
||||||
|
conditionMet = sv->value >= cond->threshold;
|
||||||
|
break;
|
||||||
|
case TRIGGER_OP_LESS_EQ:
|
||||||
|
conditionMet = sv->value <= cond->threshold;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (triggerConfig.logicOp == LOGIC_AND) {
|
||||||
|
result = result && conditionMet;
|
||||||
|
if (!result) return false;
|
||||||
|
} else {
|
||||||
|
result = result || conditionMet;
|
||||||
|
if (result) return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
void updateTrigger() {
|
||||||
|
if (!triggerConfig.enabled) return;
|
||||||
|
|
||||||
|
bool conditionsMet = checkTriggerConditions();
|
||||||
|
|
||||||
|
// Auto-start logging
|
||||||
|
if (triggerConfig.autoStart && conditionsMet && !loggingActive) {
|
||||||
|
loggingActive = true;
|
||||||
|
triggerActive = true;
|
||||||
|
loggingStartTime = millis();
|
||||||
|
// TODO: Start SD logging
|
||||||
|
Serial.println("Auto-trigger: Started logging");
|
||||||
|
}
|
||||||
|
|
||||||
|
// Auto-stop logging
|
||||||
|
if (loggingActive) {
|
||||||
|
bool shouldStop = false;
|
||||||
|
|
||||||
|
// Stop if conditions no longer met (and autoStop enabled)
|
||||||
|
if (triggerConfig.autoStop && !conditionsMet) {
|
||||||
|
shouldStop = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Stop if duration exceeded
|
||||||
|
if (triggerConfig.durationMs > 0 &&
|
||||||
|
(millis() - loggingStartTime) >= triggerConfig.durationMs) {
|
||||||
|
shouldStop = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (shouldStop) {
|
||||||
|
loggingActive = false;
|
||||||
|
triggerActive = false;
|
||||||
|
// TODO: Stop SD logging
|
||||||
|
Serial.println("Auto-trigger: Stopped logging");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool loadTriggerConfig() {
|
||||||
|
// TODO: Load from SD card
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool saveTriggerConfig() {
|
||||||
|
// TODO: Save to SD card
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void getTriggerStatusJSON(char* buffer, size_t bufferSize) {
|
||||||
|
snprintf(buffer, bufferSize,
|
||||||
|
"{\"enabled\":%s,\"active\":%s,\"logging\":%s,\"conditions\":%d,\"logic\":\"%s\"}",
|
||||||
|
triggerConfig.enabled ? "true" : "false",
|
||||||
|
triggerActive ? "true" : "false",
|
||||||
|
loggingActive ? "true" : "false",
|
||||||
|
triggerConfig.conditionCount,
|
||||||
|
triggerConfig.logicOp == LOGIC_AND ? "AND" : "OR");
|
||||||
|
}
|
||||||
85
auto_trigger.h
Normal file
85
auto_trigger.h
Normal file
@@ -0,0 +1,85 @@
|
|||||||
|
// auto_trigger.h - Auto-Logging Trigger Engine
|
||||||
|
|
||||||
|
#ifndef AUTO_TRIGGER_H
|
||||||
|
#define AUTO_TRIGGER_H
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "signal_manager.h"
|
||||||
|
|
||||||
|
// Maximum trigger conditions
|
||||||
|
#define MAX_TRIGGER_CONDITIONS 10
|
||||||
|
|
||||||
|
// Trigger operators
|
||||||
|
enum TriggerOperator {
|
||||||
|
TRIGGER_OP_GREATER,
|
||||||
|
TRIGGER_OP_LESS,
|
||||||
|
TRIGGER_OP_EQUAL,
|
||||||
|
TRIGGER_OP_GREATER_EQ,
|
||||||
|
TRIGGER_OP_LESS_EQ
|
||||||
|
};
|
||||||
|
|
||||||
|
// Logical operators between conditions
|
||||||
|
enum LogicalOperator {
|
||||||
|
LOGIC_AND,
|
||||||
|
LOGIC_OR
|
||||||
|
};
|
||||||
|
|
||||||
|
// Trigger condition
|
||||||
|
struct TriggerCondition {
|
||||||
|
char signalName[32];
|
||||||
|
TriggerOperator op;
|
||||||
|
float threshold;
|
||||||
|
bool active;
|
||||||
|
};
|
||||||
|
|
||||||
|
// Trigger configuration
|
||||||
|
struct TriggerConfig {
|
||||||
|
TriggerCondition conditions[MAX_TRIGGER_CONDITIONS];
|
||||||
|
uint8_t conditionCount;
|
||||||
|
LogicalOperator logicOp;
|
||||||
|
bool enabled;
|
||||||
|
bool autoStart;
|
||||||
|
bool autoStop;
|
||||||
|
uint32_t durationMs;
|
||||||
|
};
|
||||||
|
|
||||||
|
extern TriggerConfig triggerConfig;
|
||||||
|
extern bool triggerActive;
|
||||||
|
extern bool loggingActive;
|
||||||
|
|
||||||
|
// Initialize trigger engine
|
||||||
|
void initAutoTrigger();
|
||||||
|
|
||||||
|
// Add trigger condition
|
||||||
|
bool addTriggerCondition(const char* signalName, TriggerOperator op, float threshold);
|
||||||
|
|
||||||
|
// Remove trigger condition
|
||||||
|
bool removeTriggerCondition(uint8_t index);
|
||||||
|
|
||||||
|
// Clear all conditions
|
||||||
|
void clearTriggerConditions();
|
||||||
|
|
||||||
|
// Set logical operator
|
||||||
|
void setLogicalOperator(LogicalOperator op);
|
||||||
|
|
||||||
|
// Enable/disable trigger
|
||||||
|
void enableTrigger(bool enable);
|
||||||
|
|
||||||
|
// Set auto-start/stop
|
||||||
|
void setAutoStart(bool enable);
|
||||||
|
void setAutoStop(bool enable);
|
||||||
|
|
||||||
|
// Check trigger conditions
|
||||||
|
bool checkTriggerConditions();
|
||||||
|
|
||||||
|
// Update trigger (call periodically)
|
||||||
|
void updateTrigger();
|
||||||
|
|
||||||
|
// Load/save trigger config
|
||||||
|
bool loadTriggerConfig();
|
||||||
|
bool saveTriggerConfig();
|
||||||
|
|
||||||
|
// Get trigger status JSON
|
||||||
|
void getTriggerStatusJSON(char* buffer, size_t bufferSize);
|
||||||
|
|
||||||
|
#endif // AUTO_TRIGGER_H
|
||||||
291
can_handler.cpp
Normal file
291
can_handler.cpp
Normal file
@@ -0,0 +1,291 @@
|
|||||||
|
// can_handler.cpp - CAN FD Handler Implementation
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "can_handler.h"
|
||||||
|
#include "task_config.h"
|
||||||
|
#include "rtc_manager.h"
|
||||||
|
#include "psram_buffer.h"
|
||||||
|
|
||||||
|
ACAN2517FD canController(HSPI_CS_PIN, SPI, CAN_INT_PIN);
|
||||||
|
|
||||||
|
volatile bool canInitialized = false;
|
||||||
|
volatile uint32_t canRxCount = 0;
|
||||||
|
volatile uint32_t canTxCount = 0;
|
||||||
|
volatile uint32_t canErrorCount = 0;
|
||||||
|
volatile uint32_t canOverflowCount = 0;
|
||||||
|
static uint8_t currentCANMode = 0;
|
||||||
|
|
||||||
|
static CANFDMessage rxMessage;
|
||||||
|
static CANFDMessage txMessage;
|
||||||
|
|
||||||
|
bool initCAN() {
|
||||||
|
Serial.println("Initializing CAN FD Controller (MCP2518FD)...");
|
||||||
|
|
||||||
|
SPI.begin(HSPI_SCLK_PIN, HSPI_MISO_PIN, HSPI_MOSI_PIN, HSPI_CS_PIN);
|
||||||
|
|
||||||
|
ACAN2517FDSettings settings(
|
||||||
|
ACAN2517FDSettings::OSC_40MHz,
|
||||||
|
CAN_DEFAULT_ARBITRATION_BAUDRATE,
|
||||||
|
DataBitRateFactor::x4
|
||||||
|
);
|
||||||
|
|
||||||
|
settings.mISOCRCEnabled = true;
|
||||||
|
settings.mDriverReceiveFIFOSize = MCP2518FD_RX_FIFO_SIZE;
|
||||||
|
settings.mDriverTransmitFIFOSize = MCP2518FD_TX_FIFO_SIZE;
|
||||||
|
|
||||||
|
switch (currentCANMode) {
|
||||||
|
case 1:
|
||||||
|
settings.mRequestedMode = ACAN2517FDSettings::ListenOnly;
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
case 3:
|
||||||
|
settings.mRequestedMode = ACAN2517FDSettings::InternalLoopBack;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
settings.mRequestedMode = ACAN2517FDSettings::NormalFD;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
const uint32_t errorCode = canController.begin(settings, [] {
|
||||||
|
onCANInterrupt();
|
||||||
|
});
|
||||||
|
|
||||||
|
if (errorCode == 0) {
|
||||||
|
canInitialized = true;
|
||||||
|
Serial.println("CAN FD initialized successfully!");
|
||||||
|
Serial.printf(" Arbitration: %d bps\n", CAN_DEFAULT_ARBITRATION_BAUDRATE);
|
||||||
|
Serial.printf(" Data: %d bps\n", CAN_DEFAULT_DATA_BAUDRATE);
|
||||||
|
Serial.printf(" Mode: %d\n", currentCANMode);
|
||||||
|
return true;
|
||||||
|
} else {
|
||||||
|
Serial.printf("CAN FD initialization failed! Error: 0x%X\n", errorCode);
|
||||||
|
canInitialized = false;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool setCANMode(uint8_t mode) {
|
||||||
|
if (mode > 3) return false;
|
||||||
|
|
||||||
|
currentCANMode = mode;
|
||||||
|
|
||||||
|
if (canInitialized) {
|
||||||
|
canController.end();
|
||||||
|
canInitialized = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
return initCAN();
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t getCANMode() {
|
||||||
|
return currentCANMode;
|
||||||
|
}
|
||||||
|
|
||||||
|
void IRAM_ATTR onCANInterrupt() {
|
||||||
|
// Set flag or notify task - actual handling in task
|
||||||
|
BaseType_t xHigherPriorityTaskWoken = pdFALSE;
|
||||||
|
|
||||||
|
// Notify CAN RX task
|
||||||
|
if (canRxTaskHandle != NULL) {
|
||||||
|
vTaskNotifyGiveFromISR(canRxTaskHandle, &xHigherPriorityTaskWoken);
|
||||||
|
}
|
||||||
|
|
||||||
|
portYIELD_FROM_ISR(xHigherPriorityTaskWoken);
|
||||||
|
}
|
||||||
|
|
||||||
|
void canRxTask(void *pvParameters) {
|
||||||
|
Serial.println("CAN RX Task started on Core 0");
|
||||||
|
|
||||||
|
uint32_t framesProcessed = 0;
|
||||||
|
uint32_t lastStatusTime = 0;
|
||||||
|
|
||||||
|
while (1) {
|
||||||
|
ulTaskNotifyTake(pdTRUE, portMAX_DELAY);
|
||||||
|
|
||||||
|
uint8_t batchCount = 0;
|
||||||
|
while (canController.available() && batchCount < CAN_RX_BATCH_SIZE) {
|
||||||
|
if (canController.receive(rxMessage)) {
|
||||||
|
canRxCount++;
|
||||||
|
batchCount++;
|
||||||
|
|
||||||
|
CanFrame frame;
|
||||||
|
frame.timestamp = getMicrosTimestamp();
|
||||||
|
frame.id = rxMessage.id;
|
||||||
|
frame.len = rxMessage.len;
|
||||||
|
|
||||||
|
frame.flags = 0;
|
||||||
|
if (rxMessage.type == CANFDMessage::CANFD_WITH_BIT_RATE_SWITCH) {
|
||||||
|
frame.flags |= 0x01;
|
||||||
|
}
|
||||||
|
if (rxMessage.type == CANFDMessage::CANFD_NO_BIT_RATE_SWITCH) {
|
||||||
|
frame.flags |= 0x02;
|
||||||
|
}
|
||||||
|
|
||||||
|
memcpy(frame.data, rxMessage.data, rxMessage.len);
|
||||||
|
|
||||||
|
if (xQueueSend(canRxQueue, &frame, 0) != pdTRUE) {
|
||||||
|
if (!canFrameBuffer.push(frame)) {
|
||||||
|
canErrorCount++;
|
||||||
|
} else {
|
||||||
|
canOverflowCount++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
xQueueSend(graphQueue, &frame, 0);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
framesProcessed += batchCount;
|
||||||
|
|
||||||
|
uint32_t now = millis();
|
||||||
|
if (now - lastStatusTime > 5000) {
|
||||||
|
Serial.printf("[CAN] RX: %d, Q: %d, PSRAM: %d/%d, Err: %d\n",
|
||||||
|
canRxCount,
|
||||||
|
uxQueueMessagesWaiting(canRxQueue),
|
||||||
|
canFrameBuffer.available(),
|
||||||
|
canFrameBuffer.capacity(),
|
||||||
|
canErrorCount);
|
||||||
|
lastStatusTime = now;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void canTxTask(void *pvParameters) {
|
||||||
|
Serial.println("CAN TX Task started on Core 0");
|
||||||
|
|
||||||
|
CanTxRequest request;
|
||||||
|
|
||||||
|
while (1) {
|
||||||
|
// Wait for transmit request
|
||||||
|
if (xQueueReceive(canTxQueue, &request, portMAX_DELAY) == pdTRUE) {
|
||||||
|
// Prepare message
|
||||||
|
txMessage.id = request.id;
|
||||||
|
txMessage.len = request.len;
|
||||||
|
memcpy(txMessage.data, request.data, request.len);
|
||||||
|
txMessage.type = CANFDMessage::CANFD_WITH_BIT_RATE_SWITCH;
|
||||||
|
|
||||||
|
// Handle repeat count
|
||||||
|
uint32_t repeat = request.repeat_count;
|
||||||
|
if (repeat == 0) {
|
||||||
|
repeat = 1; // Send at least once
|
||||||
|
}
|
||||||
|
|
||||||
|
for (uint32_t i = 0; i < repeat; i++) {
|
||||||
|
if (canController.tryToSend(txMessage)) {
|
||||||
|
canTxCount++;
|
||||||
|
} else {
|
||||||
|
canErrorCount++;
|
||||||
|
Serial.println("CAN TX failed: buffer full");
|
||||||
|
}
|
||||||
|
|
||||||
|
// Delay between repeats
|
||||||
|
if (request.delay_ms > 0 && i < repeat - 1) {
|
||||||
|
vTaskDelay(pdMS_TO_TICKS(request.delay_ms));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool sendCANFrame(uint32_t id, uint8_t* data, uint8_t len, bool isFD) {
|
||||||
|
if (!canInitialized) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
CanTxRequest request;
|
||||||
|
request.id = id;
|
||||||
|
request.len = len;
|
||||||
|
memcpy(request.data, data, len);
|
||||||
|
request.delay_ms = 0;
|
||||||
|
request.repeat_count = 1;
|
||||||
|
|
||||||
|
return xQueueSend(canTxQueue, &request, pdMS_TO_TICKS(100)) == pdTRUE;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool setCANBaudrate(uint32_t arbitrationBaud, uint32_t dataBaud) {
|
||||||
|
return setCANBaudrateAndMode(arbitrationBaud, dataBaud, currentCANMode, true);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool setCANBaudrateAndMode(uint32_t arbitrationBaud, uint32_t dataBaud, uint8_t mode, bool enableFD) {
|
||||||
|
if (canInitialized) {
|
||||||
|
canController.end();
|
||||||
|
canInitialized = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
currentCANMode = mode;
|
||||||
|
|
||||||
|
DataBitRateFactor dataFactor = DataBitRateFactor::x1;
|
||||||
|
|
||||||
|
if (enableFD) {
|
||||||
|
uint32_t factor = dataBaud / arbitrationBaud;
|
||||||
|
switch (factor) {
|
||||||
|
case 1: dataFactor = DataBitRateFactor::x1; break;
|
||||||
|
case 2: dataFactor = DataBitRateFactor::x2; break;
|
||||||
|
case 4: dataFactor = DataBitRateFactor::x4; break;
|
||||||
|
case 5: dataFactor = DataBitRateFactor::x5; break;
|
||||||
|
case 6: dataFactor = DataBitRateFactor::x6; break;
|
||||||
|
case 7: dataFactor = DataBitRateFactor::x7; break;
|
||||||
|
case 8: dataFactor = DataBitRateFactor::x8; break;
|
||||||
|
case 10: dataFactor = DataBitRateFactor::x10; break;
|
||||||
|
default: dataFactor = DataBitRateFactor::x4; break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ACAN2517FDSettings settings(
|
||||||
|
ACAN2517FDSettings::OSC_40MHz,
|
||||||
|
arbitrationBaud,
|
||||||
|
dataFactor
|
||||||
|
);
|
||||||
|
|
||||||
|
settings.mISOCRCEnabled = enableFD;
|
||||||
|
settings.mDriverReceiveFIFOSize = MCP2518FD_RX_FIFO_SIZE;
|
||||||
|
settings.mDriverTransmitFIFOSize = MCP2518FD_TX_FIFO_SIZE;
|
||||||
|
|
||||||
|
if (enableFD) {
|
||||||
|
switch (mode) {
|
||||||
|
case 1:
|
||||||
|
settings.mRequestedMode = ACAN2517FDSettings::ListenOnly;
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
case 3:
|
||||||
|
settings.mRequestedMode = ACAN2517FDSettings::InternalLoopBack;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
settings.mRequestedMode = ACAN2517FDSettings::NormalFD;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
switch (mode) {
|
||||||
|
case 1:
|
||||||
|
settings.mRequestedMode = ACAN2517FDSettings::ListenOnly;
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
case 3:
|
||||||
|
settings.mRequestedMode = ACAN2517FDSettings::InternalLoopBack;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
settings.mRequestedMode = ACAN2517FDSettings::Normal20B;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
const uint32_t errorCode = canController.begin(settings, [] {
|
||||||
|
onCANInterrupt();
|
||||||
|
});
|
||||||
|
|
||||||
|
canInitialized = (errorCode == 0);
|
||||||
|
|
||||||
|
if (canInitialized) {
|
||||||
|
Serial.printf("CAN configured: Arb=%d, Data=%d, FD=%s, Mode=%d\n",
|
||||||
|
arbitrationBaud, enableFD ? dataBaud : arbitrationBaud,
|
||||||
|
enableFD ? "enabled" : "disabled", mode);
|
||||||
|
}
|
||||||
|
|
||||||
|
return canInitialized;
|
||||||
|
}
|
||||||
|
|
||||||
|
void getCANStats(uint32_t& rx, uint32_t& tx, uint32_t& errors) {
|
||||||
|
rx = canRxCount;
|
||||||
|
tx = canTxCount;
|
||||||
|
errors = canErrorCount;
|
||||||
|
}
|
||||||
51
can_handler.h
Normal file
51
can_handler.h
Normal file
@@ -0,0 +1,51 @@
|
|||||||
|
// can_handler.h - CAN FD Handler for MCP2518FD
|
||||||
|
|
||||||
|
#ifndef CAN_HANDLER_H
|
||||||
|
#define CAN_HANDLER_H
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include <ACAN2517FD.h>
|
||||||
|
#include <SPI.h>
|
||||||
|
|
||||||
|
#include "config.h"
|
||||||
|
#include "types.h"
|
||||||
|
|
||||||
|
// CAN Controller instance
|
||||||
|
extern ACAN2517FD canController;
|
||||||
|
|
||||||
|
// CAN status flags
|
||||||
|
extern volatile bool canInitialized;
|
||||||
|
extern volatile uint32_t canRxCount;
|
||||||
|
extern volatile uint32_t canTxCount;
|
||||||
|
extern volatile uint32_t canErrorCount;
|
||||||
|
extern volatile uint32_t canOverflowCount;
|
||||||
|
|
||||||
|
// Initialize CAN FD controller
|
||||||
|
bool initCAN();
|
||||||
|
|
||||||
|
// Set CAN mode (0=Normal, 1=ListenOnly, 2=Loopback, 3=ListenOnlyLoopback)
|
||||||
|
bool setCANMode(uint8_t mode);
|
||||||
|
|
||||||
|
// Get current CAN mode
|
||||||
|
uint8_t getCANMode();
|
||||||
|
|
||||||
|
// CAN RX Task (runs on Core 0)
|
||||||
|
void canRxTask(void *pvParameters);
|
||||||
|
|
||||||
|
// CAN TX Task (runs on Core 0)
|
||||||
|
void canTxTask(void *pvParameters);
|
||||||
|
|
||||||
|
// Send CAN frame
|
||||||
|
bool sendCANFrame(uint32_t id, uint8_t* data, uint8_t len, bool isFD = true);
|
||||||
|
|
||||||
|
// Set CAN baudrates
|
||||||
|
bool setCANBaudrate(uint32_t arbitrationBaud, uint32_t dataBaud);
|
||||||
|
|
||||||
|
bool setCANBaudrateAndMode(uint32_t arbitrationBaud, uint32_t dataBaud, uint8_t mode, bool enableFD = true);
|
||||||
|
|
||||||
|
void getCANStats(uint32_t& rx, uint32_t& tx, uint32_t& errors);
|
||||||
|
|
||||||
|
// Interrupt service routine (forward declaration)
|
||||||
|
void IRAM_ATTR onCANInterrupt();
|
||||||
|
|
||||||
|
#endif // CAN_HANDLER_H
|
||||||
117
config.h
Normal file
117
config.h
Normal file
@@ -0,0 +1,117 @@
|
|||||||
|
// config.h - Pin definitions and constants for ESP32-S3 CAN FD Logger
|
||||||
|
// Hardware: ESP32-S3-WROOM-1-N16R8 (16MB Flash, 8MB OPI PSRAM)
|
||||||
|
// Board Settings:
|
||||||
|
// - Board: ESP32S3 Dev Module
|
||||||
|
// - USB CDC On Boot: Enabled
|
||||||
|
// - Partition Scheme: 16M Flash (3MB APP/9.9MB FAT)
|
||||||
|
// - PSRAM: OPI PSRAM
|
||||||
|
|
||||||
|
#ifndef CONFIG_H
|
||||||
|
#define CONFIG_H
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
|
||||||
|
// =============================================================================
|
||||||
|
// HSPI Pins (CAN FD MCP2518FD)
|
||||||
|
// =============================================================================
|
||||||
|
#define HSPI_MISO_PIN 13
|
||||||
|
#define HSPI_MOSI_PIN 11
|
||||||
|
#define HSPI_SCLK_PIN 12
|
||||||
|
#define HSPI_CS_PIN 10
|
||||||
|
#define CAN_INT_PIN 3 // NOTE: GPIO3 conflicts with USB D- if USB used
|
||||||
|
|
||||||
|
// =============================================================================
|
||||||
|
// SDIO 4-bit Pins (SD Card)
|
||||||
|
// =============================================================================
|
||||||
|
#define SDIO_CLK_PIN 39
|
||||||
|
#define SDIO_CMD_PIN 38
|
||||||
|
#define SDIO_D0_PIN 40
|
||||||
|
#define SDIO_D1_PIN 41
|
||||||
|
#define SDIO_D2_PIN 42
|
||||||
|
#define SDIO_D3_PIN 21 // WARNING: Strapping pin (boot mode)
|
||||||
|
|
||||||
|
// =============================================================================
|
||||||
|
// I2C Pins (DS3231 RTC)
|
||||||
|
// =============================================================================
|
||||||
|
#define RTC_SDA_PIN 8
|
||||||
|
#define RTC_SCL_PIN 9
|
||||||
|
#define DS3231_ADDRESS 0x68
|
||||||
|
|
||||||
|
// =============================================================================
|
||||||
|
// CAN FD Settings
|
||||||
|
// =============================================================================
|
||||||
|
#define CAN_DEFAULT_ARBITRATION_BAUDRATE 500000 // 500 kbps
|
||||||
|
#define CAN_DEFAULT_DATA_BAUDRATE 2000000 // 2 Mbps (CAN FD)
|
||||||
|
#define CAN_MAX_DATA_BAUDRATE 8000000 // 8 Mbps (max)
|
||||||
|
#define CAN_OSCILLATOR_FREQ 40000000 // 40 MHz crystal
|
||||||
|
|
||||||
|
// =============================================================================
|
||||||
|
// SD Card Settings
|
||||||
|
// =============================================================================
|
||||||
|
#define SD_MOUNT_POINT "/sdcard"
|
||||||
|
#define LOGS_DIR "/logs"
|
||||||
|
#define CONFIG_DIR "/config"
|
||||||
|
#define FILE_SPLIT_SIZE (100 * 1024 * 1024) // 100 MB
|
||||||
|
#define PCAP_MAGIC_NUMBER 0xa1b2c3d4
|
||||||
|
#define PCAP_LINK_TYPE 227 // LINKTYPE_CAN_SOCKETCAN
|
||||||
|
|
||||||
|
// =============================================================================
|
||||||
|
// FreeRTOS Task Settings
|
||||||
|
// =============================================================================
|
||||||
|
#define TASK_PRIORITY_CAN_RX 5
|
||||||
|
#define TASK_PRIORITY_SD_WRITE 4
|
||||||
|
#define TASK_PRIORITY_CAN_TX 3
|
||||||
|
#define TASK_PRIORITY_WS_TX 3
|
||||||
|
#define TASK_PRIORITY_WEB_SERVER 2
|
||||||
|
#define TASK_PRIORITY_TIME_SYNC 1
|
||||||
|
|
||||||
|
#define TASK_STACK_CAN_RX 8192
|
||||||
|
#define TASK_STACK_SD_WRITE 8192
|
||||||
|
#define TASK_STACK_CAN_TX 4096
|
||||||
|
#define TASK_STACK_WS_TX 8192
|
||||||
|
#define TASK_STACK_WEB_SERVER 16384
|
||||||
|
#define TASK_STACK_TIME_SYNC 4096
|
||||||
|
|
||||||
|
// =============================================================================
|
||||||
|
// Queue Sizes (Increased for CAN FD high-speed operation)
|
||||||
|
// =============================================================================
|
||||||
|
#define QUEUE_SIZE_CAN_RX 5000 // Increased from 1000 for CAN FD burst handling
|
||||||
|
#define QUEUE_SIZE_CAN_TX 200 // Increased from 100
|
||||||
|
#define QUEUE_SIZE_GRAPH 500
|
||||||
|
|
||||||
|
// =============================================================================
|
||||||
|
// Buffer Settings
|
||||||
|
// =============================================================================
|
||||||
|
#define PSRAM_BUFFER_SIZE (256 * 1024) // 256 KB for CAN frame buffer (increased)
|
||||||
|
#define MAX_CAN_FRAMES 3200 // 256KB / ~80 bytes per frame
|
||||||
|
#define SD_WRITE_BUFFER_SIZE (8 * 1024) // 8 KB batch write buffer for SD card
|
||||||
|
|
||||||
|
// =============================================================================
|
||||||
|
// MCP2518FD FIFO Settings (Critical for zero frame loss)
|
||||||
|
// =============================================================================
|
||||||
|
#define MCP2518FD_RX_FIFO_SIZE 32 // MCP2518FD internal RX FIFO
|
||||||
|
#define MCP2518FD_TX_FIFO_SIZE 16 // MCP2518FD internal TX FIFO
|
||||||
|
|
||||||
|
// =============================================================================
|
||||||
|
// Performance Tuning
|
||||||
|
// =============================================================================
|
||||||
|
#define SD_FLUSH_INTERVAL_MS 1000 // Flush SD every 1 second (not every frame)
|
||||||
|
#define CAN_RX_BATCH_SIZE 32 // Process up to 32 frames per interrupt
|
||||||
|
#define TIMESTAMP_FROM_RTC true // Use DS3231 for drift correction
|
||||||
|
|
||||||
|
// =============================================================================
|
||||||
|
// Web Server Settings
|
||||||
|
// =============================================================================
|
||||||
|
#define WEB_SERVER_PORT 80
|
||||||
|
#define WIFI_AP_SSID "ESP32-CANLogger"
|
||||||
|
#define WIFI_AP_PASSWORD "" // Open AP (no password)
|
||||||
|
#define WIFI_AP_CHANNEL 1
|
||||||
|
#define WIFI_AP_MAX_CLIENTS 4
|
||||||
|
|
||||||
|
// =============================================================================
|
||||||
|
// Time Settings
|
||||||
|
// =============================================================================
|
||||||
|
#define NTP_SYNC_INTERVAL_MS (24 * 60 * 60 * 1000) // 24 hours
|
||||||
|
#define TIMEZONE_OFFSET_HOURS 9 // KST (Korea Standard Time)
|
||||||
|
|
||||||
|
#endif // CONFIG_H
|
||||||
240
dbc_parser.cpp
Normal file
240
dbc_parser.cpp
Normal file
@@ -0,0 +1,240 @@
|
|||||||
|
// dbc_parser.cpp - DBC Parser Implementation
|
||||||
|
|
||||||
|
#include "dbc_parser.h"
|
||||||
|
|
||||||
|
DbcDatabase dbcDB;
|
||||||
|
|
||||||
|
bool parseDBC(const char* content) {
|
||||||
|
clearDBC();
|
||||||
|
|
||||||
|
if (!content || strlen(content) == 0) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Simple DBC parser - looks for BO_ and SG_ lines
|
||||||
|
const char* ptr = content;
|
||||||
|
DbcMessage* currentMsg = nullptr;
|
||||||
|
|
||||||
|
while (*ptr) {
|
||||||
|
// Parse message definition: BO_ 123 MessageName: 8 Vector__XXX
|
||||||
|
if (strncmp(ptr, "BO_ ", 4) == 0) {
|
||||||
|
if (dbcDB.messageCount >= MAX_DBC_MESSAGES) break;
|
||||||
|
|
||||||
|
ptr += 4;
|
||||||
|
char* end;
|
||||||
|
uint32_t msgId = strtoul(ptr, &end, 10);
|
||||||
|
if (ptr == end) continue;
|
||||||
|
ptr = end;
|
||||||
|
|
||||||
|
// Skip whitespace
|
||||||
|
while (*ptr && isspace(*ptr)) ptr++;
|
||||||
|
|
||||||
|
// Read message name
|
||||||
|
char name[32];
|
||||||
|
int i = 0;
|
||||||
|
while (*ptr && *ptr != ':' && i < 31) {
|
||||||
|
name[i++] = *ptr++;
|
||||||
|
}
|
||||||
|
name[i] = '\0';
|
||||||
|
|
||||||
|
// Skip to DLC
|
||||||
|
if (*ptr == ':') ptr++;
|
||||||
|
while (*ptr && isspace(*ptr)) ptr++;
|
||||||
|
|
||||||
|
uint8_t dlc = (uint8_t)strtoul(ptr, &end, 10);
|
||||||
|
|
||||||
|
// Store message
|
||||||
|
DbcMessage* msg = &dbcDB.messages[dbcDB.messageCount++];
|
||||||
|
msg->id = msgId;
|
||||||
|
strncpy(msg->name, name, 31);
|
||||||
|
msg->dlc = dlc;
|
||||||
|
msg->signalCount = 0;
|
||||||
|
msg->signalStartIndex = dbcDB.signalCount;
|
||||||
|
currentMsg = msg;
|
||||||
|
}
|
||||||
|
// Parse signal definition: SG_ SignalName : 0|16@1+ (0.1,0) [0|6553.5] "V" Vector__XXX
|
||||||
|
else if (strncmp(ptr, " SG_ ", 5) == 0 && currentMsg) {
|
||||||
|
if (dbcDB.signalCount >= MAX_DBC_SIGNALS) break;
|
||||||
|
|
||||||
|
ptr += 5;
|
||||||
|
|
||||||
|
// Read signal name
|
||||||
|
char name[32];
|
||||||
|
int i = 0;
|
||||||
|
while (*ptr && *ptr != ':' && i < 31) {
|
||||||
|
name[i++] = *ptr++;
|
||||||
|
}
|
||||||
|
name[i] = '\0';
|
||||||
|
|
||||||
|
// Skip to startBit|length
|
||||||
|
if (*ptr == ':') ptr++;
|
||||||
|
while (*ptr && isspace(*ptr)) ptr++;
|
||||||
|
|
||||||
|
// Parse startBit|length@endian+signed
|
||||||
|
char* end;
|
||||||
|
uint32_t startBit = strtoul(ptr, &end, 10);
|
||||||
|
if (*end != '|') continue;
|
||||||
|
ptr = end + 1;
|
||||||
|
|
||||||
|
uint32_t length = strtoul(ptr, &end, 10);
|
||||||
|
if (*end != '@') continue;
|
||||||
|
ptr = end + 1;
|
||||||
|
|
||||||
|
bool isLittleEndian = (*ptr == '1');
|
||||||
|
ptr++;
|
||||||
|
|
||||||
|
bool isSigned = (*ptr == '-');
|
||||||
|
ptr++;
|
||||||
|
|
||||||
|
// Skip to factor,offset
|
||||||
|
while (*ptr && *ptr != '(') ptr++;
|
||||||
|
if (*ptr == '(') ptr++;
|
||||||
|
|
||||||
|
float factor = strtof(ptr, &end);
|
||||||
|
if (*end != ',') continue;
|
||||||
|
ptr = end + 1;
|
||||||
|
|
||||||
|
float offset = strtof(ptr, &end);
|
||||||
|
|
||||||
|
// Store signal
|
||||||
|
DbcSignal* sig = &dbcDB.signals[dbcDB.signalCount++];
|
||||||
|
strncpy(sig->name, name, 31);
|
||||||
|
sig->startBit = startBit;
|
||||||
|
sig->length = length;
|
||||||
|
sig->isLittleEndian = isLittleEndian;
|
||||||
|
sig->isSigned = isSigned;
|
||||||
|
sig->factor = factor;
|
||||||
|
sig->offset = offset;
|
||||||
|
sig->min = 0;
|
||||||
|
sig->max = 0;
|
||||||
|
sig->unit[0] = '\0';
|
||||||
|
sig->messageId = currentMsg->id;
|
||||||
|
|
||||||
|
currentMsg->signalCount++;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Move to next line
|
||||||
|
while (*ptr && *ptr != '\n') ptr++;
|
||||||
|
if (*ptr == '\n') ptr++;
|
||||||
|
}
|
||||||
|
|
||||||
|
dbcDB.loaded = (dbcDB.messageCount > 0);
|
||||||
|
return dbcDB.loaded;
|
||||||
|
}
|
||||||
|
|
||||||
|
DbcMessage* getMessageById(uint32_t id) {
|
||||||
|
for (uint16_t i = 0; i < dbcDB.messageCount; i++) {
|
||||||
|
if (dbcDB.messages[i].id == id) {
|
||||||
|
return &dbcDB.messages[i];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
|
DbcSignal* getSignalByName(DbcMessage* msg, const char* name) {
|
||||||
|
if (!msg) return nullptr;
|
||||||
|
|
||||||
|
for (uint16_t i = 0; i < msg->signalCount; i++) {
|
||||||
|
DbcSignal* sig = &dbcDB.signals[msg->signalStartIndex + i];
|
||||||
|
if (strcmp(sig->name, name) == 0) {
|
||||||
|
return sig;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t getSignalsForMessage(uint32_t msgId, DbcSignal** signals) {
|
||||||
|
DbcMessage* msg = getMessageById(msgId);
|
||||||
|
if (!msg) return 0;
|
||||||
|
|
||||||
|
*signals = &dbcDB.signals[msg->signalStartIndex];
|
||||||
|
return msg->signalCount;
|
||||||
|
}
|
||||||
|
|
||||||
|
float extractSignalValue(const uint8_t* data, const DbcSignal* signal) {
|
||||||
|
if (!data || !signal) return 0.0f;
|
||||||
|
|
||||||
|
uint64_t rawValue = 0;
|
||||||
|
uint32_t startBit = signal->startBit;
|
||||||
|
uint32_t length = signal->length;
|
||||||
|
|
||||||
|
if (signal->isLittleEndian) {
|
||||||
|
// Little endian: startBit is from LSB
|
||||||
|
uint32_t byteOffset = startBit / 8;
|
||||||
|
uint32_t bitOffset = startBit % 8;
|
||||||
|
|
||||||
|
for (uint32_t i = 0; i < length; i++) {
|
||||||
|
uint32_t bitPos = bitOffset + i;
|
||||||
|
uint32_t bytePos = byteOffset + (bitPos / 8);
|
||||||
|
uint32_t bitInByte = bitPos % 8;
|
||||||
|
|
||||||
|
if (bytePos < 64) {
|
||||||
|
bool bitSet = (data[bytePos] >> bitInByte) & 0x01;
|
||||||
|
if (bitSet) {
|
||||||
|
rawValue |= (1ULL << i);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
// Big endian: startBit is from MSB
|
||||||
|
for (uint32_t i = 0; i < length; i++) {
|
||||||
|
uint32_t bitPos = startBit - i;
|
||||||
|
uint32_t bytePos = bitPos / 8;
|
||||||
|
uint32_t bitInByte = 7 - (bitPos % 8);
|
||||||
|
|
||||||
|
if (bytePos < 64) {
|
||||||
|
bool bitSet = (data[bytePos] >> bitInByte) & 0x01;
|
||||||
|
if (bitSet) {
|
||||||
|
rawValue |= (1ULL << (length - 1 - i));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Handle signed values
|
||||||
|
if (signal->isSigned) {
|
||||||
|
if (rawValue & (1ULL << (length - 1))) {
|
||||||
|
// Negative number - sign extend
|
||||||
|
rawValue |= (~0ULL) << length;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Apply factor and offset
|
||||||
|
float physicalValue = ((float)(int64_t)rawValue) * signal->factor + signal->offset;
|
||||||
|
|
||||||
|
return physicalValue;
|
||||||
|
}
|
||||||
|
|
||||||
|
void clearDBC() {
|
||||||
|
dbcDB.messageCount = 0;
|
||||||
|
dbcDB.signalCount = 0;
|
||||||
|
dbcDB.loaded = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool loadDBCFromSD(const char* filename) {
|
||||||
|
// TODO: Implement SD card file loading
|
||||||
|
// This would read the file and call parseDBC()
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void getDBCSummary(char* buffer, size_t bufferSize) {
|
||||||
|
if (!dbcDB.loaded) {
|
||||||
|
strncpy(buffer, "{\"loaded\":false}", bufferSize);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
int pos = snprintf(buffer, bufferSize, "{\"loaded\":true,\"messages\":[%d],\"signals\":[%d],\"msgs\":[",
|
||||||
|
dbcDB.messageCount, dbcDB.signalCount);
|
||||||
|
|
||||||
|
for (uint16_t i = 0; i < dbcDB.messageCount && pos < (int)bufferSize - 100; i++) {
|
||||||
|
if (i > 0) {
|
||||||
|
pos += snprintf(buffer + pos, bufferSize - pos, ",");
|
||||||
|
}
|
||||||
|
DbcMessage* msg = &dbcDB.messages[i];
|
||||||
|
pos += snprintf(buffer + pos, bufferSize - pos,
|
||||||
|
"{\"id\":%u,\"name\":\"%s\",\"dlc\":%d,\"sigCount\":%d}",
|
||||||
|
msg->id, msg->name, msg->dlc, msg->signalCount);
|
||||||
|
}
|
||||||
|
|
||||||
|
strncat(buffer, "]}", bufferSize - pos - 1);
|
||||||
|
}
|
||||||
71
dbc_parser.h
Normal file
71
dbc_parser.h
Normal file
@@ -0,0 +1,71 @@
|
|||||||
|
// dbc_parser.h - DBC File Parser for CAN Database
|
||||||
|
|
||||||
|
#ifndef DBC_PARSER_H
|
||||||
|
#define DBC_PARSER_H
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
|
||||||
|
// Maximum number of messages and signals
|
||||||
|
#define MAX_DBC_MESSAGES 100
|
||||||
|
#define MAX_DBC_SIGNALS 500
|
||||||
|
|
||||||
|
// Signal structure
|
||||||
|
struct DbcSignal {
|
||||||
|
char name[32];
|
||||||
|
uint32_t startBit;
|
||||||
|
uint32_t length;
|
||||||
|
bool isLittleEndian;
|
||||||
|
bool isSigned;
|
||||||
|
float factor;
|
||||||
|
float offset;
|
||||||
|
float min;
|
||||||
|
float max;
|
||||||
|
char unit[8];
|
||||||
|
uint32_t messageId;
|
||||||
|
};
|
||||||
|
|
||||||
|
// Message structure
|
||||||
|
struct DbcMessage {
|
||||||
|
uint32_t id;
|
||||||
|
char name[32];
|
||||||
|
uint8_t dlc;
|
||||||
|
uint16_t signalCount;
|
||||||
|
uint16_t signalStartIndex;
|
||||||
|
};
|
||||||
|
|
||||||
|
// DBC database
|
||||||
|
struct DbcDatabase {
|
||||||
|
DbcMessage messages[MAX_DBC_MESSAGES];
|
||||||
|
DbcSignal signals[MAX_DBC_SIGNALS];
|
||||||
|
uint16_t messageCount;
|
||||||
|
uint16_t signalCount;
|
||||||
|
bool loaded;
|
||||||
|
};
|
||||||
|
|
||||||
|
extern DbcDatabase dbcDB;
|
||||||
|
|
||||||
|
// Parse DBC file content
|
||||||
|
bool parseDBC(const char* content);
|
||||||
|
|
||||||
|
// Get message by ID
|
||||||
|
DbcMessage* getMessageById(uint32_t id);
|
||||||
|
|
||||||
|
// Get signal from message by name
|
||||||
|
DbcSignal* getSignalByName(DbcMessage* msg, const char* name);
|
||||||
|
|
||||||
|
// Get all signals for a message
|
||||||
|
uint16_t getSignalsForMessage(uint32_t msgId, DbcSignal** signals);
|
||||||
|
|
||||||
|
// Extract signal value from raw CAN data
|
||||||
|
float extractSignalValue(const uint8_t* data, const DbcSignal* signal);
|
||||||
|
|
||||||
|
// Clear database
|
||||||
|
void clearDBC();
|
||||||
|
|
||||||
|
// Load DBC from SD card
|
||||||
|
bool loadDBCFromSD(const char* filename);
|
||||||
|
|
||||||
|
// Save parsed DBC info to JSON for web
|
||||||
|
void getDBCSummary(char* buffer, size_t bufferSize);
|
||||||
|
|
||||||
|
#endif // DBC_PARSER_H
|
||||||
65
esp32_canfd_logger.ino
Normal file
65
esp32_canfd_logger.ino
Normal file
@@ -0,0 +1,65 @@
|
|||||||
|
// ESP32-S3 CAN FD Logger with WiFi Real-time Display
|
||||||
|
// Main entry point for Arduino IDE
|
||||||
|
// Board: ESP32S3 Dev Module
|
||||||
|
|
||||||
|
#include "config.h"
|
||||||
|
#include "task_config.h"
|
||||||
|
#include "can_handler.h"
|
||||||
|
#include "sd_logger.h"
|
||||||
|
#include "rtc_manager.h"
|
||||||
|
#include "web_server.h"
|
||||||
|
#include "dbc_parser.h"
|
||||||
|
#include "signal_manager.h"
|
||||||
|
#include "auto_trigger.h"
|
||||||
|
#include "psram_buffer.h"
|
||||||
|
#include "test_handler.h"
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
Serial.begin(115200);
|
||||||
|
delay(1000);
|
||||||
|
|
||||||
|
Serial.println("================================");
|
||||||
|
Serial.println("ESP32-S3 CAN FD Logger");
|
||||||
|
Serial.println("Version 2.0 - PSRAM Optimized");
|
||||||
|
Serial.println("================================");
|
||||||
|
|
||||||
|
if (psramFound()) {
|
||||||
|
Serial.printf("PSRAM found: %d MB\n", ESP.getPsramSize() / (1024 * 1024));
|
||||||
|
} else {
|
||||||
|
Serial.println("WARNING: PSRAM not found!");
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!initPSRAMBuffers()) {
|
||||||
|
Serial.println("PSRAM buffer initialization failed!");
|
||||||
|
}
|
||||||
|
|
||||||
|
initFreeRTOSResources();
|
||||||
|
initRTC();
|
||||||
|
initSDCard();
|
||||||
|
createLogDirectories();
|
||||||
|
initCAN();
|
||||||
|
initSignalManager();
|
||||||
|
initAutoTrigger();
|
||||||
|
initTestHandler();
|
||||||
|
createAllTasks();
|
||||||
|
|
||||||
|
printMemoryStatus();
|
||||||
|
|
||||||
|
Serial.println("System ready!");
|
||||||
|
Serial.printf("AP SSID: %s\n", WIFI_AP_SSID);
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
static uint32_t lastCheck = 0;
|
||||||
|
|
||||||
|
if (millis() - lastCheck > 30000) {
|
||||||
|
lastCheck = millis();
|
||||||
|
Serial.printf("[Status] Heap: %d KB, PSRAM: %d KB, Buffer: %d/%d frames\n",
|
||||||
|
ESP.getFreeHeap() / 1024,
|
||||||
|
ESP.getFreePsram() / 1024,
|
||||||
|
canFrameBuffer.available(),
|
||||||
|
canFrameBuffer.capacity());
|
||||||
|
}
|
||||||
|
|
||||||
|
vTaskDelay(pdMS_TO_TICKS(1000));
|
||||||
|
}
|
||||||
264
psram_buffer.cpp
Normal file
264
psram_buffer.cpp
Normal file
@@ -0,0 +1,264 @@
|
|||||||
|
// psram_buffer.cpp - PSRAM-based Ring Buffer Implementation
|
||||||
|
|
||||||
|
#include "psram_buffer.h"
|
||||||
|
#include "config.h"
|
||||||
|
|
||||||
|
PSRAMRingBuffer canFrameBuffer;
|
||||||
|
|
||||||
|
static uint8_t* sdWriteBuffer = nullptr;
|
||||||
|
static uint8_t* signalBuffer = nullptr;
|
||||||
|
static bool psramInitialized = false;
|
||||||
|
|
||||||
|
PSRAMRingBuffer::PSRAMRingBuffer()
|
||||||
|
: _buffer(nullptr), _capacity(0), _head(0), _tail(0), _count(0), _mutex(nullptr) {
|
||||||
|
}
|
||||||
|
|
||||||
|
PSRAMRingBuffer::~PSRAMRingBuffer() {
|
||||||
|
if (_buffer != nullptr) {
|
||||||
|
free(_buffer);
|
||||||
|
_buffer = nullptr;
|
||||||
|
}
|
||||||
|
if (_mutex != nullptr) {
|
||||||
|
vSemaphoreDelete(_mutex);
|
||||||
|
_mutex = nullptr;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool PSRAMRingBuffer::begin(size_t capacity) {
|
||||||
|
if (_buffer != nullptr) {
|
||||||
|
free(_buffer);
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t bytesNeeded = capacity * sizeof(CanFrame);
|
||||||
|
|
||||||
|
if (psramFound()) {
|
||||||
|
_buffer = (CanFrame*)ps_malloc(bytesNeeded);
|
||||||
|
Serial.printf("[PSRAM] Allocated %d bytes for %d frames\n", bytesNeeded, capacity);
|
||||||
|
} else {
|
||||||
|
_buffer = (CanFrame*)malloc(bytesNeeded);
|
||||||
|
Serial.printf("[HEAP] Allocated %d bytes for %d frames\n", bytesNeeded, capacity);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (_buffer == nullptr) {
|
||||||
|
Serial.println("[ERROR] Failed to allocate ring buffer!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
memset(_buffer, 0, bytesNeeded);
|
||||||
|
_capacity = capacity;
|
||||||
|
_head = 0;
|
||||||
|
_tail = 0;
|
||||||
|
_count = 0;
|
||||||
|
|
||||||
|
_mutex = xSemaphoreCreateMutex();
|
||||||
|
if (_mutex == nullptr) {
|
||||||
|
free(_buffer);
|
||||||
|
_buffer = nullptr;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool PSRAMRingBuffer::push(const CanFrame& frame) {
|
||||||
|
if (_buffer == nullptr || _mutex == nullptr) return false;
|
||||||
|
|
||||||
|
if (xSemaphoreTake(_mutex, pdMS_TO_TICKS(10)) != pdTRUE) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (_count >= _capacity) {
|
||||||
|
_tail = (_tail + 1) % _capacity;
|
||||||
|
_count--;
|
||||||
|
}
|
||||||
|
|
||||||
|
_buffer[_head] = frame;
|
||||||
|
_head = (_head + 1) % _capacity;
|
||||||
|
_count++;
|
||||||
|
|
||||||
|
xSemaphoreGive(_mutex);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool PSRAMRingBuffer::pop(CanFrame& frame) {
|
||||||
|
if (_buffer == nullptr || _mutex == nullptr) return false;
|
||||||
|
|
||||||
|
if (xSemaphoreTake(_mutex, pdMS_TO_TICKS(10)) != pdTRUE) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (_count == 0) {
|
||||||
|
xSemaphoreGive(_mutex);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
frame = _buffer[_tail];
|
||||||
|
_tail = (_tail + 1) % _capacity;
|
||||||
|
_count--;
|
||||||
|
|
||||||
|
xSemaphoreGive(_mutex);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool PSRAMRingBuffer::peek(CanFrame& frame) {
|
||||||
|
if (_buffer == nullptr || _mutex == nullptr || _count == 0) return false;
|
||||||
|
|
||||||
|
if (xSemaphoreTake(_mutex, pdMS_TO_TICKS(10)) != pdTRUE) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
frame = _buffer[_tail];
|
||||||
|
xSemaphoreGive(_mutex);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t PSRAMRingBuffer::available() {
|
||||||
|
return _count;
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t PSRAMRingBuffer::capacity() {
|
||||||
|
return _capacity;
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t PSRAMRingBuffer::freeSpace() {
|
||||||
|
return _capacity - _count;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool PSRAMRingBuffer::isFull() {
|
||||||
|
return _count >= _capacity;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool PSRAMRingBuffer::isEmpty() {
|
||||||
|
return _count == 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void PSRAMRingBuffer::clear() {
|
||||||
|
if (_mutex != nullptr && xSemaphoreTake(_mutex, pdMS_TO_TICKS(100)) == pdTRUE) {
|
||||||
|
_head = 0;
|
||||||
|
_tail = 0;
|
||||||
|
_count = 0;
|
||||||
|
xSemaphoreGive(_mutex);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void PSRAMRingBuffer::flush() {
|
||||||
|
clear();
|
||||||
|
}
|
||||||
|
|
||||||
|
CanFrame* PSRAMRingBuffer::getBuffer() {
|
||||||
|
return _buffer;
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t PSRAMRingBuffer::getHead() {
|
||||||
|
return _head;
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t PSRAMRingBuffer::getTail() {
|
||||||
|
return _tail;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool initPSRAMBuffers() {
|
||||||
|
Serial.println("Initializing PSRAM buffers...");
|
||||||
|
|
||||||
|
if (psramFound()) {
|
||||||
|
Serial.printf("PSRAM detected: %d MB\n", ESP.getPsramSize() / (1024 * 1024));
|
||||||
|
} else {
|
||||||
|
Serial.println("WARNING: PSRAM not found! Using heap memory.");
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t frameCount = MAX_PSRAM_CAN_FRAMES;
|
||||||
|
if (!canFrameBuffer.begin(frameCount)) {
|
||||||
|
Serial.println("Failed to initialize CAN frame buffer!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (psramFound()) {
|
||||||
|
sdWriteBuffer = (uint8_t*)ps_malloc(PSRAM_SD_BUFFER_SIZE);
|
||||||
|
signalBuffer = (uint8_t*)ps_malloc(PSRAM_SIGNAL_BUFFER_SIZE);
|
||||||
|
} else {
|
||||||
|
sdWriteBuffer = (uint8_t*)malloc(PSRAM_SD_BUFFER_SIZE);
|
||||||
|
signalBuffer = (uint8_t*)malloc(PSRAM_SIGNAL_BUFFER_SIZE);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (sdWriteBuffer == nullptr || signalBuffer == nullptr) {
|
||||||
|
Serial.println("Failed to allocate auxiliary buffers!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
memset(sdWriteBuffer, 0, PSRAM_SD_BUFFER_SIZE);
|
||||||
|
memset(signalBuffer, 0, PSRAM_SIGNAL_BUFFER_SIZE);
|
||||||
|
|
||||||
|
psramInitialized = true;
|
||||||
|
|
||||||
|
Serial.printf("CAN frame buffer: %d frames (%d KB)\n",
|
||||||
|
frameCount, (frameCount * sizeof(CanFrame)) / 1024);
|
||||||
|
Serial.printf("SD write buffer: %d KB\n", PSRAM_SD_BUFFER_SIZE / 1024);
|
||||||
|
Serial.printf("Signal buffer: %d KB\n", PSRAM_SIGNAL_BUFFER_SIZE / 1024);
|
||||||
|
|
||||||
|
printMemoryStatus();
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void deinitPSRAMBuffers() {
|
||||||
|
canFrameBuffer.~PSRAMRingBuffer();
|
||||||
|
|
||||||
|
if (sdWriteBuffer != nullptr) {
|
||||||
|
free(sdWriteBuffer);
|
||||||
|
sdWriteBuffer = nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (signalBuffer != nullptr) {
|
||||||
|
free(signalBuffer);
|
||||||
|
signalBuffer = nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
|
psramInitialized = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t* getSDWriteBuffer() {
|
||||||
|
return sdWriteBuffer;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t* getSignalBuffer() {
|
||||||
|
return signalBuffer;
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t getFreePSRAM() {
|
||||||
|
if (psramFound()) {
|
||||||
|
return ESP.getFreePsram();
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t getUsedPSRAM() {
|
||||||
|
if (psramFound()) {
|
||||||
|
return ESP.getPsramSize() - ESP.getFreePsram();
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t getTotalPSRAM() {
|
||||||
|
if (psramFound()) {
|
||||||
|
return ESP.getPsramSize();
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void printMemoryStatus() {
|
||||||
|
Serial.println("========== Memory Status ==========");
|
||||||
|
Serial.printf("Heap: %d / %d KB (free / total)\n",
|
||||||
|
ESP.getFreeHeap() / 1024,
|
||||||
|
ESP.getHeapSize() / 1024);
|
||||||
|
|
||||||
|
if (psramFound()) {
|
||||||
|
Serial.printf("PSRAM: %d / %d KB (free / total)\n",
|
||||||
|
ESP.getFreePsram() / 1024,
|
||||||
|
ESP.getPsramSize() / 1024);
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial.printf("CAN Buffer: %d / %d frames used\n",
|
||||||
|
canFrameBuffer.available(),
|
||||||
|
canFrameBuffer.capacity());
|
||||||
|
Serial.println("===================================");
|
||||||
|
}
|
||||||
58
psram_buffer.h
Normal file
58
psram_buffer.h
Normal file
@@ -0,0 +1,58 @@
|
|||||||
|
// psram_buffer.h - PSRAM-based Ring Buffer for CAN FD Logger
|
||||||
|
|
||||||
|
#ifndef PSRAM_BUFFER_H
|
||||||
|
#define PSRAM_BUFFER_H
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "types.h"
|
||||||
|
|
||||||
|
#define PSRAM_CAN_BUFFER_SIZE (512 * 1024)
|
||||||
|
#define PSRAM_SD_BUFFER_SIZE (16 * 1024)
|
||||||
|
#define PSRAM_SIGNAL_BUFFER_SIZE (4 * 1024)
|
||||||
|
|
||||||
|
#define MAX_PSRAM_CAN_FRAMES (PSRAM_CAN_BUFFER_SIZE / sizeof(CanFrame))
|
||||||
|
|
||||||
|
class PSRAMRingBuffer {
|
||||||
|
public:
|
||||||
|
PSRAMRingBuffer();
|
||||||
|
~PSRAMRingBuffer();
|
||||||
|
|
||||||
|
bool begin(size_t capacity);
|
||||||
|
bool push(const CanFrame& frame);
|
||||||
|
bool pop(CanFrame& frame);
|
||||||
|
bool peek(CanFrame& frame);
|
||||||
|
size_t available();
|
||||||
|
size_t capacity();
|
||||||
|
size_t freeSpace();
|
||||||
|
bool isFull();
|
||||||
|
bool isEmpty();
|
||||||
|
void clear();
|
||||||
|
void flush();
|
||||||
|
|
||||||
|
CanFrame* getBuffer();
|
||||||
|
size_t getHead();
|
||||||
|
size_t getTail();
|
||||||
|
|
||||||
|
private:
|
||||||
|
CanFrame* _buffer;
|
||||||
|
size_t _capacity;
|
||||||
|
volatile size_t _head;
|
||||||
|
volatile size_t _tail;
|
||||||
|
volatile size_t _count;
|
||||||
|
SemaphoreHandle_t _mutex;
|
||||||
|
};
|
||||||
|
|
||||||
|
extern PSRAMRingBuffer canFrameBuffer;
|
||||||
|
|
||||||
|
bool initPSRAMBuffers();
|
||||||
|
void deinitPSRAMBuffers();
|
||||||
|
|
||||||
|
uint8_t* getSDWriteBuffer();
|
||||||
|
uint8_t* getSignalBuffer();
|
||||||
|
|
||||||
|
size_t getFreePSRAM();
|
||||||
|
size_t getUsedPSRAM();
|
||||||
|
size_t getTotalPSRAM();
|
||||||
|
void printMemoryStatus();
|
||||||
|
|
||||||
|
#endif // PSRAM_BUFFER_H
|
||||||
136
rtc_manager.cpp
Normal file
136
rtc_manager.cpp
Normal file
@@ -0,0 +1,136 @@
|
|||||||
|
// rtc_manager.cpp - RTC Manager Implementation
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "rtc_manager.h"
|
||||||
|
#include "task_config.h"
|
||||||
|
|
||||||
|
RTC_DS3231 rtc;
|
||||||
|
bool rtcInitialized = false;
|
||||||
|
|
||||||
|
bool initRTC() {
|
||||||
|
Serial.println("Initializing DS3231 RTC...");
|
||||||
|
|
||||||
|
// Initialize I2C
|
||||||
|
Wire.begin(RTC_SDA_PIN, RTC_SCL_PIN);
|
||||||
|
|
||||||
|
// Initialize RTC
|
||||||
|
if (!rtc.begin()) {
|
||||||
|
Serial.println("RTC not found!");
|
||||||
|
rtcInitialized = false;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Check if RTC is running
|
||||||
|
if (rtc.lostPower()) {
|
||||||
|
Serial.println("RTC lost power, setting default time!");
|
||||||
|
// Set to compile time
|
||||||
|
rtc.adjust(DateTime(F(__DATE__), F(__TIME__)));
|
||||||
|
}
|
||||||
|
|
||||||
|
// Sync system time from RTC
|
||||||
|
syncSystemTimeFromRTC();
|
||||||
|
|
||||||
|
rtcInitialized = true;
|
||||||
|
Serial.println("RTC initialized successfully!");
|
||||||
|
Serial.print(" Current time: ");
|
||||||
|
Serial.println(getRTCTimeString());
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool isRTCRunning() {
|
||||||
|
return rtcInitialized && !rtc.lostPower();
|
||||||
|
}
|
||||||
|
|
||||||
|
void setRTCTime(uint32_t unixtime) {
|
||||||
|
if (!rtcInitialized) return;
|
||||||
|
|
||||||
|
rtc.adjust(DateTime(unixtime));
|
||||||
|
syncSystemTimeFromRTC();
|
||||||
|
|
||||||
|
Serial.printf("RTC time set to: %s\n", getRTCTimeString().c_str());
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t getRTCTime() {
|
||||||
|
if (!rtcInitialized) return 0;
|
||||||
|
|
||||||
|
DateTime now = rtc.now();
|
||||||
|
return now.unixtime();
|
||||||
|
}
|
||||||
|
|
||||||
|
String getRTCTimeString() {
|
||||||
|
if (!rtcInitialized) return String("RTC Not Initialized");
|
||||||
|
|
||||||
|
DateTime now = rtc.now();
|
||||||
|
char buffer[25];
|
||||||
|
snprintf(buffer, sizeof(buffer), "%04d-%02d-%02d %02d:%02d:%02d",
|
||||||
|
now.year(), now.month(), now.day(),
|
||||||
|
now.hour(), now.minute(), now.second());
|
||||||
|
return String(buffer);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool syncTimeFromNTP() {
|
||||||
|
// This will be called from WiFi STA mode
|
||||||
|
// Implementation depends on WiFi connection
|
||||||
|
// For now, placeholder
|
||||||
|
Serial.println("NTP sync requested (requires WiFi STA mode)");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void timeSyncTask(void *pvParameters) {
|
||||||
|
Serial.println("Time Sync Task started on Core 1");
|
||||||
|
|
||||||
|
static uint32_t lastNTPSync = 0;
|
||||||
|
static uint32_t lastRTCSync = 0;
|
||||||
|
const uint32_t RTC_SYNC_INTERVAL_MS = 3600000;
|
||||||
|
|
||||||
|
while (1) {
|
||||||
|
uint32_t now = millis();
|
||||||
|
|
||||||
|
if (now - lastNTPSync > NTP_SYNC_INTERVAL_MS) {
|
||||||
|
lastNTPSync = now;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (now - lastRTCSync > RTC_SYNC_INTERVAL_MS) {
|
||||||
|
if (rtcInitialized) {
|
||||||
|
syncSystemTimeFromRTC();
|
||||||
|
Serial.printf("[RTC] System time synced: %s\n", getRTCTimeString().c_str());
|
||||||
|
}
|
||||||
|
lastRTCSync = now;
|
||||||
|
}
|
||||||
|
|
||||||
|
vTaskDelay(pdMS_TO_TICKS(60000));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
uint64_t getMicrosTimestamp() {
|
||||||
|
// Get current time in microseconds
|
||||||
|
struct timeval tv;
|
||||||
|
gettimeofday(&tv, NULL);
|
||||||
|
return (uint64_t)tv.tv_sec * 1000000ULL + tv.tv_usec;
|
||||||
|
}
|
||||||
|
|
||||||
|
String unixTimeToString(uint32_t unixtime) {
|
||||||
|
time_t t = unixtime;
|
||||||
|
struct tm* timeinfo = localtime(&t);
|
||||||
|
|
||||||
|
char buffer[25];
|
||||||
|
strftime(buffer, sizeof(buffer), "%Y-%m-%d %H:%M:%S", timeinfo);
|
||||||
|
return String(buffer);
|
||||||
|
}
|
||||||
|
|
||||||
|
void syncSystemTimeFromRTC() {
|
||||||
|
if (!rtcInitialized) return;
|
||||||
|
|
||||||
|
DateTime now = rtc.now();
|
||||||
|
|
||||||
|
struct timeval tv;
|
||||||
|
tv.tv_sec = now.unixtime();
|
||||||
|
tv.tv_usec = 0;
|
||||||
|
|
||||||
|
settimeofday(&tv, NULL);
|
||||||
|
|
||||||
|
// Set timezone (KST = UTC+9)
|
||||||
|
setenv("TZ", "KST-9", 1);
|
||||||
|
tzset();
|
||||||
|
}
|
||||||
50
rtc_manager.h
Normal file
50
rtc_manager.h
Normal file
@@ -0,0 +1,50 @@
|
|||||||
|
// rtc_manager.h - RTC Manager for DS3231
|
||||||
|
|
||||||
|
#ifndef RTC_MANAGER_H
|
||||||
|
#define RTC_MANAGER_H
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include <RTClib.h>
|
||||||
|
#include <Wire.h>
|
||||||
|
#include <time.h>
|
||||||
|
|
||||||
|
#include "config.h"
|
||||||
|
#include "task_config.h"
|
||||||
|
|
||||||
|
// RTC instance
|
||||||
|
extern RTC_DS3231 rtc;
|
||||||
|
|
||||||
|
// RTC status
|
||||||
|
extern bool rtcInitialized;
|
||||||
|
|
||||||
|
// Initialize RTC
|
||||||
|
bool initRTC();
|
||||||
|
|
||||||
|
// Check if RTC is running
|
||||||
|
bool isRTCRunning();
|
||||||
|
|
||||||
|
// Set RTC time (Unix timestamp)
|
||||||
|
void setRTCTime(uint32_t unixtime);
|
||||||
|
|
||||||
|
// Get RTC time (Unix timestamp)
|
||||||
|
uint32_t getRTCTime();
|
||||||
|
|
||||||
|
// Get formatted time string
|
||||||
|
String getRTCTimeString();
|
||||||
|
|
||||||
|
// Sync time from NTP (WiFi STA mode)
|
||||||
|
bool syncTimeFromNTP();
|
||||||
|
|
||||||
|
// Time Sync Task (runs on Core 1)
|
||||||
|
void timeSyncTask(void *pvParameters);
|
||||||
|
|
||||||
|
// Get current timestamp in microseconds
|
||||||
|
uint64_t getMicrosTimestamp();
|
||||||
|
|
||||||
|
// Convert Unix time to formatted string
|
||||||
|
String unixTimeToString(uint32_t unixtime);
|
||||||
|
|
||||||
|
// Set system time from RTC
|
||||||
|
void syncSystemTimeFromRTC();
|
||||||
|
|
||||||
|
#endif // RTC_MANAGER_H
|
||||||
342
sd_logger.cpp
Normal file
342
sd_logger.cpp
Normal file
@@ -0,0 +1,342 @@
|
|||||||
|
// sd_logger.cpp - SD Card Logger Implementation with Batch Writing
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "sd_logger.h"
|
||||||
|
#include "task_config.h"
|
||||||
|
#include "can_handler.h"
|
||||||
|
#include "psram_buffer.h"
|
||||||
|
|
||||||
|
extern volatile uint32_t canErrorCount;
|
||||||
|
|
||||||
|
bool sdInitialized = false;
|
||||||
|
uint64_t sdCardSize = 0;
|
||||||
|
uint64_t sdFreeSpace = 0;
|
||||||
|
|
||||||
|
File currentLogFile;
|
||||||
|
char currentLogFileName[64] = {0};
|
||||||
|
uint32_t currentLogFileSize = 0;
|
||||||
|
|
||||||
|
static uint32_t fileSequenceNumber = 0;
|
||||||
|
|
||||||
|
static uint8_t* writeBuffer = nullptr;
|
||||||
|
static size_t bufferOffset = 0;
|
||||||
|
static uint32_t lastFlushTime = 0;
|
||||||
|
static uint32_t framesInBuffer = 0;
|
||||||
|
|
||||||
|
bool initSDCard() {
|
||||||
|
Serial.println("Initializing SD Card (SDIO 4-bit mode)...");
|
||||||
|
|
||||||
|
writeBuffer = getSDWriteBuffer();
|
||||||
|
if (writeBuffer == nullptr) {
|
||||||
|
if (psramFound()) {
|
||||||
|
writeBuffer = (uint8_t*)ps_malloc(PSRAM_SD_BUFFER_SIZE);
|
||||||
|
} else {
|
||||||
|
writeBuffer = (uint8_t*)malloc(PSRAM_SD_BUFFER_SIZE);
|
||||||
|
}
|
||||||
|
if (writeBuffer == nullptr) {
|
||||||
|
Serial.println("Failed to allocate SD write buffer!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
SD_MMC.setPins(SDIO_CLK_PIN, SDIO_CMD_PIN, SDIO_D0_PIN,
|
||||||
|
SDIO_D1_PIN, SDIO_D2_PIN, SDIO_D3_PIN);
|
||||||
|
|
||||||
|
if (!SD_MMC.begin("/sdcard", false)) {
|
||||||
|
Serial.println("SD Card mount failed!");
|
||||||
|
sdInitialized = false;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
sdCardSize = SD_MMC.cardSize();
|
||||||
|
sdFreeSpace = SD_MMC.totalBytes() - SD_MMC.usedBytes();
|
||||||
|
|
||||||
|
Serial.println("SD Card mounted successfully!");
|
||||||
|
Serial.printf(" Card Size: %llu MB\n", sdCardSize / (1024 * 1024));
|
||||||
|
Serial.printf(" Free Space: %llu MB\n", sdFreeSpace / (1024 * 1024));
|
||||||
|
|
||||||
|
sdInitialized = true;
|
||||||
|
|
||||||
|
createLogDirectories();
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool createLogDirectories() {
|
||||||
|
if (!sdInitialized) return false;
|
||||||
|
|
||||||
|
// Create logs directory
|
||||||
|
if (!SD_MMC.exists(LOGS_DIR)) {
|
||||||
|
if (SD_MMC.mkdir(LOGS_DIR)) {
|
||||||
|
Serial.println("Created /logs directory");
|
||||||
|
} else {
|
||||||
|
Serial.println("Failed to create /logs directory");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Create config directory
|
||||||
|
if (!SD_MMC.exists(CONFIG_DIR)) {
|
||||||
|
if (SD_MMC.mkdir(CONFIG_DIR)) {
|
||||||
|
Serial.println("Created /config directory");
|
||||||
|
} else {
|
||||||
|
Serial.println("Failed to create /config directory");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool startLogFile() {
|
||||||
|
if (!sdInitialized) return false;
|
||||||
|
|
||||||
|
// Close current file if open
|
||||||
|
closeLogFile();
|
||||||
|
|
||||||
|
// Generate filename with timestamp
|
||||||
|
time_t now = time(NULL);
|
||||||
|
struct tm* timeinfo = localtime(&now);
|
||||||
|
|
||||||
|
snprintf(currentLogFileName, sizeof(currentLogFileName),
|
||||||
|
"%s/CAN_%04d%02d%02d_%02d%02d%02d_%03d.pcap",
|
||||||
|
LOGS_DIR,
|
||||||
|
timeinfo->tm_year + 1900,
|
||||||
|
timeinfo->tm_mon + 1,
|
||||||
|
timeinfo->tm_mday,
|
||||||
|
timeinfo->tm_hour,
|
||||||
|
timeinfo->tm_min,
|
||||||
|
timeinfo->tm_sec,
|
||||||
|
fileSequenceNumber++);
|
||||||
|
|
||||||
|
// Open file for writing
|
||||||
|
currentLogFile = SD_MMC.open(currentLogFileName, FILE_WRITE);
|
||||||
|
if (!currentLogFile) {
|
||||||
|
Serial.printf("Failed to open log file: %s\n", currentLogFileName);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Write PCAP global header
|
||||||
|
PCAPGlobalHeader header;
|
||||||
|
header.magicNumber = PCAP_MAGIC_NUMBER;
|
||||||
|
header.versionMajor = 2;
|
||||||
|
header.versionMinor = 4;
|
||||||
|
header.thiszone = 0;
|
||||||
|
header.sigfigs = 0;
|
||||||
|
header.snaplen = 65535;
|
||||||
|
header.network = PCAP_LINK_TYPE;
|
||||||
|
|
||||||
|
currentLogFile.write((uint8_t*)&header, sizeof(header));
|
||||||
|
currentLogFileSize = sizeof(header);
|
||||||
|
|
||||||
|
Serial.printf("Started new log file: %s\n", currentLogFileName);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void closeLogFile() {
|
||||||
|
flushWriteBuffer();
|
||||||
|
if (currentLogFile) {
|
||||||
|
currentLogFile.close();
|
||||||
|
Serial.printf("Closed log file: %s\n", currentLogFileName);
|
||||||
|
currentLogFileName[0] = '\0';
|
||||||
|
currentLogFileSize = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool writeCANFrameToSD(const CanFrame& frame) {
|
||||||
|
if (!sdInitialized || !currentLogFile) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (currentLogFileSize >= FILE_SPLIT_SIZE) {
|
||||||
|
flushWriteBuffer();
|
||||||
|
closeLogFile();
|
||||||
|
if (!startLogFile()) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
PCAPPacketHeader pktHeader;
|
||||||
|
pktHeader.tsSec = (uint32_t)(frame.timestamp / 1000000ULL);
|
||||||
|
pktHeader.tsUsec = (uint32_t)(frame.timestamp % 1000000ULL);
|
||||||
|
|
||||||
|
CANFDFrame canFrame;
|
||||||
|
canFrame.canId = frame.id;
|
||||||
|
canFrame.len = frame.len;
|
||||||
|
canFrame.flags = frame.flags;
|
||||||
|
canFrame.reserved0 = 0;
|
||||||
|
canFrame.reserved1 = 0;
|
||||||
|
memcpy(canFrame.data, frame.data, frame.len);
|
||||||
|
|
||||||
|
uint32_t frameSize = sizeof(CANFDFrame) - 64 + frame.len;
|
||||||
|
pktHeader.inclLen = frameSize;
|
||||||
|
pktHeader.origLen = frameSize;
|
||||||
|
|
||||||
|
size_t totalSize = sizeof(pktHeader) + frameSize;
|
||||||
|
|
||||||
|
if (bufferOffset + totalSize > PSRAM_SD_BUFFER_SIZE) {
|
||||||
|
if (!flushWriteBuffer()) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (xSemaphoreTake(sdMutex, pdMS_TO_TICKS(100)) == pdTRUE) {
|
||||||
|
memcpy(writeBuffer + bufferOffset, &pktHeader, sizeof(pktHeader));
|
||||||
|
bufferOffset += sizeof(pktHeader);
|
||||||
|
memcpy(writeBuffer + bufferOffset, &canFrame, frameSize);
|
||||||
|
bufferOffset += frameSize;
|
||||||
|
framesInBuffer++;
|
||||||
|
currentLogFileSize += totalSize;
|
||||||
|
|
||||||
|
xSemaphoreGive(sdMutex);
|
||||||
|
|
||||||
|
uint32_t now = millis();
|
||||||
|
if (now - lastFlushTime >= SD_FLUSH_INTERVAL_MS) {
|
||||||
|
flushWriteBuffer();
|
||||||
|
lastFlushTime = now;
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool flushWriteBuffer() {
|
||||||
|
if (bufferOffset == 0 || !currentLogFile) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (xSemaphoreTake(sdMutex, pdMS_TO_TICKS(500)) == pdTRUE) {
|
||||||
|
size_t written = currentLogFile.write(writeBuffer, bufferOffset);
|
||||||
|
currentLogFile.flush();
|
||||||
|
|
||||||
|
xSemaphoreGive(sdMutex);
|
||||||
|
|
||||||
|
if (written != bufferOffset) {
|
||||||
|
Serial.printf("SD write incomplete: %d of %d bytes\n", written, bufferOffset);
|
||||||
|
bufferOffset = 0;
|
||||||
|
framesInBuffer = 0;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bufferOffset = 0;
|
||||||
|
framesInBuffer = 0;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void sdWriteTask(void *pvParameters) {
|
||||||
|
Serial.println("SD Write Task started on Core 1");
|
||||||
|
|
||||||
|
CanFrame frame;
|
||||||
|
uint32_t lastStatusTime = 0;
|
||||||
|
uint32_t framesWritten = 0;
|
||||||
|
uint32_t framesFromPSRAM = 0;
|
||||||
|
|
||||||
|
while (1) {
|
||||||
|
bool gotFrame = false;
|
||||||
|
|
||||||
|
if (xQueueReceive(canRxQueue, &frame, pdMS_TO_TICKS(10)) == pdTRUE) {
|
||||||
|
gotFrame = true;
|
||||||
|
} else if (canFrameBuffer.available() > 0) {
|
||||||
|
if (canFrameBuffer.pop(frame)) {
|
||||||
|
gotFrame = true;
|
||||||
|
framesFromPSRAM++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gotFrame) {
|
||||||
|
if (!writeCANFrameToSD(frame)) {
|
||||||
|
canErrorCount++;
|
||||||
|
} else {
|
||||||
|
framesWritten++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t now = millis();
|
||||||
|
if (now - lastStatusTime > 10000) {
|
||||||
|
Serial.printf("[SD] Written: %d, From PSRAM: %d, Buffer: %d, Q: %d, PSRAM: %d\n",
|
||||||
|
framesWritten, framesFromPSRAM, bufferOffset,
|
||||||
|
uxQueueMessagesWaiting(canRxQueue),
|
||||||
|
canFrameBuffer.available());
|
||||||
|
lastStatusTime = now;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
uint64_t getSDCardSize() {
|
||||||
|
return sdInitialized ? sdCardSize : 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint64_t getFreeSpace() {
|
||||||
|
if (!sdInitialized) return 0;
|
||||||
|
return SD_MMC.totalBytes() - SD_MMC.usedBytes();
|
||||||
|
}
|
||||||
|
|
||||||
|
uint64_t getUsedSpace() {
|
||||||
|
if (!sdInitialized) return 0;
|
||||||
|
return SD_MMC.usedBytes();
|
||||||
|
}
|
||||||
|
|
||||||
|
int listLogFiles(char* buffer, size_t bufferSize) {
|
||||||
|
if (!sdInitialized) return 0;
|
||||||
|
|
||||||
|
File root = SD_MMC.open(LOGS_DIR);
|
||||||
|
if (!root || !root.isDirectory()) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
int count = 0;
|
||||||
|
size_t offset = 0;
|
||||||
|
|
||||||
|
File file = root.openNextFile();
|
||||||
|
while (file && offset < bufferSize - 128) {
|
||||||
|
if (!file.isDirectory() && strstr(file.name(), ".pcap")) {
|
||||||
|
int len = snprintf(buffer + offset, bufferSize - offset,
|
||||||
|
"{\"name\":\"%s\",\"size\":%d},",
|
||||||
|
file.name(), file.size());
|
||||||
|
offset += len;
|
||||||
|
count++;
|
||||||
|
}
|
||||||
|
file = root.openNextFile();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Remove trailing comma
|
||||||
|
if (offset > 0 && buffer[offset - 1] == ',') {
|
||||||
|
buffer[offset - 1] = '\0';
|
||||||
|
}
|
||||||
|
|
||||||
|
return count;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool getLogFileInfo(const char* filename, uint32_t& size, uint32_t& timestamp) {
|
||||||
|
if (!sdInitialized) return false;
|
||||||
|
|
||||||
|
char path[128];
|
||||||
|
snprintf(path, sizeof(path), "%s/%s", LOGS_DIR, filename);
|
||||||
|
|
||||||
|
File file = SD_MMC.open(path);
|
||||||
|
if (!file) return false;
|
||||||
|
|
||||||
|
size = file.size();
|
||||||
|
timestamp = file.getLastWrite();
|
||||||
|
file.close();
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool deleteLogFile(const char* filename) {
|
||||||
|
if (!sdInitialized) return false;
|
||||||
|
|
||||||
|
char path[128];
|
||||||
|
snprintf(path, sizeof(path), "%s/%s", LOGS_DIR, filename);
|
||||||
|
|
||||||
|
return SD_MMC.remove(path);
|
||||||
|
}
|
||||||
|
|
||||||
|
const char* getCurrentLogFilename() {
|
||||||
|
return currentLogFileName;
|
||||||
|
}
|
||||||
90
sd_logger.h
Normal file
90
sd_logger.h
Normal file
@@ -0,0 +1,90 @@
|
|||||||
|
// sd_logger.h - SD Card Logger with PCAP format
|
||||||
|
|
||||||
|
#ifndef SD_LOGGER_H
|
||||||
|
#define SD_LOGGER_H
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include <SD_MMC.h>
|
||||||
|
#include <FS.h>
|
||||||
|
|
||||||
|
#include "config.h"
|
||||||
|
#include "types.h"
|
||||||
|
|
||||||
|
// SD status
|
||||||
|
extern bool sdInitialized;
|
||||||
|
extern uint64_t sdCardSize;
|
||||||
|
extern uint64_t sdFreeSpace;
|
||||||
|
|
||||||
|
// Current log file
|
||||||
|
extern File currentLogFile;
|
||||||
|
extern char currentLogFileName[64];
|
||||||
|
extern uint32_t currentLogFileSize;
|
||||||
|
|
||||||
|
// Initialize SD card
|
||||||
|
bool initSDCard();
|
||||||
|
|
||||||
|
// Create log directories
|
||||||
|
bool createLogDirectories();
|
||||||
|
|
||||||
|
// Start new log file
|
||||||
|
bool startLogFile();
|
||||||
|
|
||||||
|
// Close current log file
|
||||||
|
void closeLogFile();
|
||||||
|
|
||||||
|
// Write CAN frame to SD (PCAP format)
|
||||||
|
bool writeCANFrameToSD(const CanFrame& frame);
|
||||||
|
|
||||||
|
// Flush write buffer to SD card
|
||||||
|
bool flushWriteBuffer();
|
||||||
|
|
||||||
|
// SD Write Task (runs on Core 1)
|
||||||
|
void sdWriteTask(void *pvParameters);
|
||||||
|
|
||||||
|
// Get SD card info
|
||||||
|
uint64_t getSDCardSize();
|
||||||
|
uint64_t getFreeSpace();
|
||||||
|
uint64_t getUsedSpace();
|
||||||
|
|
||||||
|
// List log files
|
||||||
|
int listLogFiles(char* buffer, size_t bufferSize);
|
||||||
|
|
||||||
|
// Get file info
|
||||||
|
bool getLogFileInfo(const char* filename, uint32_t& size, uint32_t& timestamp);
|
||||||
|
|
||||||
|
// Delete log file
|
||||||
|
bool deleteLogFile(const char* filename);
|
||||||
|
|
||||||
|
// Get current filename
|
||||||
|
const char* getCurrentLogFilename();
|
||||||
|
|
||||||
|
// PCAP file structures
|
||||||
|
#pragma pack(push, 1)
|
||||||
|
struct PCAPGlobalHeader {
|
||||||
|
uint32_t magicNumber; // 0xa1b2c3d4
|
||||||
|
uint16_t versionMajor; // 2
|
||||||
|
uint16_t versionMinor; // 4
|
||||||
|
int32_t thiszone; // GMT to local correction
|
||||||
|
uint32_t sigfigs; // accuracy of timestamps
|
||||||
|
uint32_t snaplen; // max length of captured packets
|
||||||
|
uint32_t network; // data link type (227 = LINKTYPE_CAN_SOCKETCAN)
|
||||||
|
};
|
||||||
|
|
||||||
|
struct PCAPPacketHeader {
|
||||||
|
uint32_t tsSec; // timestamp seconds
|
||||||
|
uint32_t tsUsec; // timestamp microseconds
|
||||||
|
uint32_t inclLen; // number of octets of packet saved in file
|
||||||
|
uint32_t origLen; // actual length of packet
|
||||||
|
};
|
||||||
|
|
||||||
|
struct CANFDFrame {
|
||||||
|
uint32_t canId; // CAN ID + flags
|
||||||
|
uint8_t len; // payload length
|
||||||
|
uint8_t flags; // FD flags
|
||||||
|
uint8_t reserved0;
|
||||||
|
uint8_t reserved1;
|
||||||
|
uint8_t data[64]; // payload
|
||||||
|
};
|
||||||
|
#pragma pack(pop)
|
||||||
|
|
||||||
|
#endif // SD_LOGGER_H
|
||||||
189
signal_manager.cpp
Normal file
189
signal_manager.cpp
Normal file
@@ -0,0 +1,189 @@
|
|||||||
|
// signal_manager.cpp - Signal Manager Implementation
|
||||||
|
|
||||||
|
#include "signal_manager.h"
|
||||||
|
|
||||||
|
SignalDefinition signalDefs[MAX_MANUAL_SIGNALS];
|
||||||
|
uint16_t signalDefCount = 0;
|
||||||
|
SignalValue signalValues[MAX_MANUAL_SIGNALS];
|
||||||
|
|
||||||
|
void initSignalManager() {
|
||||||
|
signalDefCount = 0;
|
||||||
|
for (int i = 0; i < MAX_MANUAL_SIGNALS; i++) {
|
||||||
|
signalDefs[i].enabled = false;
|
||||||
|
signalValues[i].valid = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Try to load saved signals
|
||||||
|
loadSignalsFromSD();
|
||||||
|
}
|
||||||
|
|
||||||
|
bool addManualSignal(const char* name, uint32_t canId, uint32_t startBit,
|
||||||
|
uint32_t length, bool isLittleEndian, bool isSigned,
|
||||||
|
float factor, float offset) {
|
||||||
|
if (signalDefCount >= MAX_MANUAL_SIGNALS) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Check if signal already exists
|
||||||
|
for (uint16_t i = 0; i < signalDefCount; i++) {
|
||||||
|
if (strcmp(signalDefs[i].name, name) == 0) {
|
||||||
|
// Update existing
|
||||||
|
signalDefs[i].canId = canId;
|
||||||
|
signalDefs[i].startBit = startBit;
|
||||||
|
signalDefs[i].length = length;
|
||||||
|
signalDefs[i].isLittleEndian = isLittleEndian;
|
||||||
|
signalDefs[i].isSigned = isSigned;
|
||||||
|
signalDefs[i].factor = factor;
|
||||||
|
signalDefs[i].offset = offset;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Add new signal
|
||||||
|
SignalDefinition* sig = &signalDefs[signalDefCount++];
|
||||||
|
strncpy(sig->name, name, 31);
|
||||||
|
sig->canId = canId;
|
||||||
|
sig->startBit = startBit;
|
||||||
|
sig->length = length;
|
||||||
|
sig->isLittleEndian = isLittleEndian;
|
||||||
|
sig->isSigned = isSigned;
|
||||||
|
sig->factor = factor;
|
||||||
|
sig->offset = offset;
|
||||||
|
sig->source = SIGNAL_SOURCE_MANUAL;
|
||||||
|
sig->enabled = true;
|
||||||
|
|
||||||
|
// Initialize value slot
|
||||||
|
strncpy(signalValues[signalDefCount - 1].name, name, 31);
|
||||||
|
signalValues[signalDefCount - 1].value = 0;
|
||||||
|
signalValues[signalDefCount - 1].valid = false;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool removeSignal(const char* name) {
|
||||||
|
for (uint16_t i = 0; i < signalDefCount; i++) {
|
||||||
|
if (strcmp(signalDefs[i].name, name) == 0) {
|
||||||
|
// Shift remaining signals
|
||||||
|
for (uint16_t j = i; j < signalDefCount - 1; j++) {
|
||||||
|
signalDefs[j] = signalDefs[j + 1];
|
||||||
|
signalValues[j] = signalValues[j + 1];
|
||||||
|
}
|
||||||
|
signalDefCount--;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool enableSignal(const char* name, bool enable) {
|
||||||
|
SignalDefinition* sig = getSignalDef(name);
|
||||||
|
if (sig) {
|
||||||
|
sig->enabled = enable;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
SignalDefinition* getSignalDef(const char* name) {
|
||||||
|
for (uint16_t i = 0; i < signalDefCount; i++) {
|
||||||
|
if (strcmp(signalDefs[i].name, name) == 0) {
|
||||||
|
return &signalDefs[i];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
|
SignalValue* getSignalValue(const char* name) {
|
||||||
|
for (uint16_t i = 0; i < signalDefCount; i++) {
|
||||||
|
if (strcmp(signalValues[i].name, name) == 0) {
|
||||||
|
return &signalValues[i];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
|
void updateSignalFromCAN(const CanFrame* frame) {
|
||||||
|
if (!frame) return;
|
||||||
|
|
||||||
|
// Check DBC signals first
|
||||||
|
if (dbcDB.loaded) {
|
||||||
|
DbcMessage* msg = getMessageById(frame->id);
|
||||||
|
if (msg) {
|
||||||
|
DbcSignal* signals;
|
||||||
|
uint16_t count = getSignalsForMessage(frame->id, &signals);
|
||||||
|
for (uint16_t i = 0; i < count; i++) {
|
||||||
|
float value = extractSignalValue(frame->data, &signals[i]);
|
||||||
|
|
||||||
|
// Update signal value if we have a matching manual signal
|
||||||
|
SignalValue* sv = getSignalValue(signals[i].name);
|
||||||
|
if (sv) {
|
||||||
|
sv->value = value;
|
||||||
|
sv->timestamp = frame->timestamp / 1000; // Convert to ms
|
||||||
|
sv->valid = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Check manual signals
|
||||||
|
for (uint16_t i = 0; i < signalDefCount; i++) {
|
||||||
|
if (signalDefs[i].canId == frame->id && signalDefs[i].enabled) {
|
||||||
|
// Create a temporary DbcSignal for extraction
|
||||||
|
DbcSignal tempSig;
|
||||||
|
strncpy(tempSig.name, signalDefs[i].name, 32);
|
||||||
|
tempSig.startBit = signalDefs[i].startBit;
|
||||||
|
tempSig.length = signalDefs[i].length;
|
||||||
|
tempSig.isLittleEndian = signalDefs[i].isLittleEndian;
|
||||||
|
tempSig.isSigned = signalDefs[i].isSigned;
|
||||||
|
tempSig.factor = signalDefs[i].factor;
|
||||||
|
tempSig.offset = signalDefs[i].offset;
|
||||||
|
|
||||||
|
float value = extractSignalValue(frame->data, &tempSig);
|
||||||
|
signalValues[i].value = value;
|
||||||
|
signalValues[i].timestamp = frame->timestamp / 1000;
|
||||||
|
signalValues[i].valid = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void updateAllSignals(const CanFrame* frame) {
|
||||||
|
updateSignalFromCAN(frame);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t getEnabledSignals(SignalValue* values, uint16_t maxCount) {
|
||||||
|
uint16_t count = 0;
|
||||||
|
for (uint16_t i = 0; i < signalDefCount && count < maxCount; i++) {
|
||||||
|
if (signalDefs[i].enabled && signalValues[i].valid) {
|
||||||
|
values[count++] = signalValues[i];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return count;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool loadSignalsFromSD() {
|
||||||
|
// TODO: Implement loading from SD card
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool saveSignalsToSD() {
|
||||||
|
// TODO: Implement saving to SD card
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void getSignalsJSON(char* buffer, size_t bufferSize) {
|
||||||
|
int pos = snprintf(buffer, bufferSize, "{\"count\":%d,\"signals\":[", signalDefCount);
|
||||||
|
|
||||||
|
for (uint16_t i = 0; i < signalDefCount && pos < (int)bufferSize - 100; i++) {
|
||||||
|
if (i > 0) {
|
||||||
|
pos += snprintf(buffer + pos, bufferSize - pos, ",");
|
||||||
|
}
|
||||||
|
SignalDefinition* sig = &signalDefs[i];
|
||||||
|
pos += snprintf(buffer + pos, bufferSize - pos,
|
||||||
|
"{\"name\":\"%s\",\"canId\":\"0x%X\",\"startBit\":%d,\"length\":%d,\"enabled\":%s,\"value\":%.2f}",
|
||||||
|
sig->name, sig->canId, sig->startBit, sig->length,
|
||||||
|
sig->enabled ? "true" : "false",
|
||||||
|
signalValues[i].value);
|
||||||
|
}
|
||||||
|
|
||||||
|
strncat(buffer, "]}", bufferSize - pos - 1);
|
||||||
|
}
|
||||||
86
signal_manager.h
Normal file
86
signal_manager.h
Normal file
@@ -0,0 +1,86 @@
|
|||||||
|
// signal_manager.h - Signal Manager for CAN Signal Definitions
|
||||||
|
|
||||||
|
#ifndef SIGNAL_MANAGER_H
|
||||||
|
#define SIGNAL_MANAGER_H
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "dbc_parser.h"
|
||||||
|
#include "types.h"
|
||||||
|
|
||||||
|
// Maximum manual signals
|
||||||
|
#define MAX_MANUAL_SIGNALS 50
|
||||||
|
|
||||||
|
// Signal definition types
|
||||||
|
enum SignalSource {
|
||||||
|
SIGNAL_SOURCE_NONE,
|
||||||
|
SIGNAL_SOURCE_DBC,
|
||||||
|
SIGNAL_SOURCE_MANUAL
|
||||||
|
};
|
||||||
|
|
||||||
|
// Signal definition (for manual and DBC signals)
|
||||||
|
struct SignalDefinition {
|
||||||
|
char name[32];
|
||||||
|
uint32_t canId;
|
||||||
|
uint32_t startBit;
|
||||||
|
uint32_t length;
|
||||||
|
bool isLittleEndian;
|
||||||
|
bool isSigned;
|
||||||
|
float factor;
|
||||||
|
float offset;
|
||||||
|
SignalSource source;
|
||||||
|
bool enabled;
|
||||||
|
uint32_t dbcSignalIndex;
|
||||||
|
};
|
||||||
|
|
||||||
|
// Signal value (for real-time data)
|
||||||
|
struct SignalValue {
|
||||||
|
char name[32];
|
||||||
|
float value;
|
||||||
|
uint32_t timestamp;
|
||||||
|
bool valid;
|
||||||
|
};
|
||||||
|
|
||||||
|
// Signal manager
|
||||||
|
extern SignalDefinition signalDefs[MAX_MANUAL_SIGNALS];
|
||||||
|
extern uint16_t signalDefCount;
|
||||||
|
extern SignalValue signalValues[MAX_MANUAL_SIGNALS];
|
||||||
|
|
||||||
|
// Initialize signal manager
|
||||||
|
void initSignalManager();
|
||||||
|
|
||||||
|
// Add manual signal definition
|
||||||
|
bool addManualSignal(const char* name, uint32_t canId, uint32_t startBit,
|
||||||
|
uint32_t length, bool isLittleEndian, bool isSigned,
|
||||||
|
float factor, float offset);
|
||||||
|
|
||||||
|
// Remove signal definition
|
||||||
|
bool removeSignal(const char* name);
|
||||||
|
|
||||||
|
// Enable/disable signal for graphing
|
||||||
|
bool enableSignal(const char* name, bool enable);
|
||||||
|
|
||||||
|
// Get signal definition by name
|
||||||
|
SignalDefinition* getSignalDef(const char* name);
|
||||||
|
|
||||||
|
// Get signal value by name
|
||||||
|
SignalValue* getSignalValue(const char* name);
|
||||||
|
|
||||||
|
// Update signal value from CAN frame
|
||||||
|
void updateSignalFromCAN(const CanFrame* frame);
|
||||||
|
|
||||||
|
// Update all signal values from current CAN data
|
||||||
|
void updateAllSignals(const CanFrame* frame);
|
||||||
|
|
||||||
|
// Get enabled signals for WebSocket
|
||||||
|
uint16_t getEnabledSignals(SignalValue* values, uint16_t maxCount);
|
||||||
|
|
||||||
|
// Load signals from SD
|
||||||
|
bool loadSignalsFromSD();
|
||||||
|
|
||||||
|
// Save signals to SD
|
||||||
|
bool saveSignalsToSD();
|
||||||
|
|
||||||
|
// Get signals JSON for web
|
||||||
|
void getSignalsJSON(char* buffer, size_t bufferSize);
|
||||||
|
|
||||||
|
#endif // SIGNAL_MANAGER_H
|
||||||
221
task_config.cpp
Normal file
221
task_config.cpp
Normal file
@@ -0,0 +1,221 @@
|
|||||||
|
// task_config.cpp - FreeRTOS Resource Implementation
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "config.h"
|
||||||
|
#include "types.h"
|
||||||
|
#include "task_config.h"
|
||||||
|
|
||||||
|
TaskHandle_t canRxTaskHandle = NULL;
|
||||||
|
TaskHandle_t sdWriteTaskHandle = NULL;
|
||||||
|
TaskHandle_t canTxTaskHandle = NULL;
|
||||||
|
TaskHandle_t wsTxTaskHandle = NULL;
|
||||||
|
TaskHandle_t webServerTaskHandle = NULL;
|
||||||
|
TaskHandle_t timeSyncTaskHandle = NULL;
|
||||||
|
|
||||||
|
QueueHandle_t canRxQueue = NULL;
|
||||||
|
QueueHandle_t canTxQueue = NULL;
|
||||||
|
QueueHandle_t graphQueue = NULL;
|
||||||
|
|
||||||
|
SemaphoreHandle_t configMutex = NULL;
|
||||||
|
SemaphoreHandle_t sdMutex = NULL;
|
||||||
|
SemaphoreHandle_t rtcMutex = NULL;
|
||||||
|
SemaphoreHandle_t canMutex = NULL;
|
||||||
|
|
||||||
|
bool initFreeRTOSResources() {
|
||||||
|
Serial.println("Initializing FreeRTOS resources...");
|
||||||
|
|
||||||
|
canRxQueue = xQueueCreate(QUEUE_SIZE_CAN_RX, sizeof(CanFrame));
|
||||||
|
if (canRxQueue == NULL) {
|
||||||
|
Serial.println("Failed to create canRxQueue!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
canTxQueue = xQueueCreate(QUEUE_SIZE_CAN_TX, sizeof(CanTxRequest));
|
||||||
|
if (canTxQueue == NULL) {
|
||||||
|
Serial.println("Failed to create canTxQueue!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
graphQueue = xQueueCreate(QUEUE_SIZE_GRAPH, sizeof(CanFrame));
|
||||||
|
if (graphQueue == NULL) {
|
||||||
|
Serial.println("Failed to create graphQueue!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
configMutex = xSemaphoreCreateMutex();
|
||||||
|
if (configMutex == NULL) {
|
||||||
|
Serial.println("Failed to create configMutex!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
sdMutex = xSemaphoreCreateMutex();
|
||||||
|
if (sdMutex == NULL) {
|
||||||
|
Serial.println("Failed to create sdMutex!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
rtcMutex = xSemaphoreCreateMutex();
|
||||||
|
if (rtcMutex == NULL) {
|
||||||
|
Serial.println("Failed to create rtcMutex!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
canMutex = xSemaphoreCreateMutex();
|
||||||
|
if (canMutex == NULL) {
|
||||||
|
Serial.println("Failed to create canMutex!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial.println("FreeRTOS resources initialized successfully!");
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool createAllTasks() {
|
||||||
|
Serial.println("Creating FreeRTOS tasks...");
|
||||||
|
|
||||||
|
BaseType_t result;
|
||||||
|
|
||||||
|
result = xTaskCreatePinnedToCore(
|
||||||
|
canRxTask,
|
||||||
|
"CAN_RX",
|
||||||
|
TASK_STACK_CAN_RX,
|
||||||
|
NULL,
|
||||||
|
TASK_PRIORITY_CAN_RX,
|
||||||
|
&canRxTaskHandle,
|
||||||
|
CORE_0
|
||||||
|
);
|
||||||
|
if (result != pdPASS) {
|
||||||
|
Serial.println("Failed to create canRxTask!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
result = xTaskCreatePinnedToCore(
|
||||||
|
sdWriteTask,
|
||||||
|
"SD_WRITE",
|
||||||
|
TASK_STACK_SD_WRITE,
|
||||||
|
NULL,
|
||||||
|
TASK_PRIORITY_SD_WRITE,
|
||||||
|
&sdWriteTaskHandle,
|
||||||
|
CORE_1
|
||||||
|
);
|
||||||
|
if (result != pdPASS) {
|
||||||
|
Serial.println("Failed to create sdWriteTask!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
result = xTaskCreatePinnedToCore(
|
||||||
|
canTxTask,
|
||||||
|
"CAN_TX",
|
||||||
|
TASK_STACK_CAN_TX,
|
||||||
|
NULL,
|
||||||
|
TASK_PRIORITY_CAN_TX,
|
||||||
|
&canTxTaskHandle,
|
||||||
|
CORE_0
|
||||||
|
);
|
||||||
|
if (result != pdPASS) {
|
||||||
|
Serial.println("Failed to create canTxTask!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
result = xTaskCreatePinnedToCore(
|
||||||
|
webServerTask,
|
||||||
|
"WEB_SRV",
|
||||||
|
TASK_STACK_WEB_SERVER,
|
||||||
|
NULL,
|
||||||
|
TASK_PRIORITY_WEB_SERVER,
|
||||||
|
&webServerTaskHandle,
|
||||||
|
CORE_1
|
||||||
|
);
|
||||||
|
if (result != pdPASS) {
|
||||||
|
Serial.println("Failed to create webServerTask!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
result = xTaskCreatePinnedToCore(
|
||||||
|
wsTxTask,
|
||||||
|
"WS_TX",
|
||||||
|
TASK_STACK_WS_TX,
|
||||||
|
NULL,
|
||||||
|
TASK_PRIORITY_WS_TX,
|
||||||
|
&wsTxTaskHandle,
|
||||||
|
CORE_1
|
||||||
|
);
|
||||||
|
if (result != pdPASS) {
|
||||||
|
Serial.println("Failed to create wsTxTask!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
result = xTaskCreatePinnedToCore(
|
||||||
|
timeSyncTask,
|
||||||
|
"TIME_SYNC",
|
||||||
|
TASK_STACK_TIME_SYNC,
|
||||||
|
NULL,
|
||||||
|
TASK_PRIORITY_TIME_SYNC,
|
||||||
|
&timeSyncTaskHandle,
|
||||||
|
CORE_1
|
||||||
|
);
|
||||||
|
if (result != pdPASS) {
|
||||||
|
Serial.println("Failed to create timeSyncTask!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial.println("All tasks created successfully!");
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void deleteAllTasks() {
|
||||||
|
if (canRxTaskHandle != NULL) {
|
||||||
|
vTaskDelete(canRxTaskHandle);
|
||||||
|
canRxTaskHandle = NULL;
|
||||||
|
}
|
||||||
|
if (sdWriteTaskHandle != NULL) {
|
||||||
|
vTaskDelete(sdWriteTaskHandle);
|
||||||
|
sdWriteTaskHandle = NULL;
|
||||||
|
}
|
||||||
|
if (canTxTaskHandle != NULL) {
|
||||||
|
vTaskDelete(canTxTaskHandle);
|
||||||
|
canTxTaskHandle = NULL;
|
||||||
|
}
|
||||||
|
if (wsTxTaskHandle != NULL) {
|
||||||
|
vTaskDelete(wsTxTaskHandle);
|
||||||
|
wsTxTaskHandle = NULL;
|
||||||
|
}
|
||||||
|
if (webServerTaskHandle != NULL) {
|
||||||
|
vTaskDelete(webServerTaskHandle);
|
||||||
|
webServerTaskHandle = NULL;
|
||||||
|
}
|
||||||
|
if (timeSyncTaskHandle != NULL) {
|
||||||
|
vTaskDelete(timeSyncTaskHandle);
|
||||||
|
timeSyncTaskHandle = NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (canRxQueue != NULL) {
|
||||||
|
vQueueDelete(canRxQueue);
|
||||||
|
canRxQueue = NULL;
|
||||||
|
}
|
||||||
|
if (canTxQueue != NULL) {
|
||||||
|
vQueueDelete(canTxQueue);
|
||||||
|
canTxQueue = NULL;
|
||||||
|
}
|
||||||
|
if (graphQueue != NULL) {
|
||||||
|
vQueueDelete(graphQueue);
|
||||||
|
graphQueue = NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (configMutex != NULL) {
|
||||||
|
vSemaphoreDelete(configMutex);
|
||||||
|
configMutex = NULL;
|
||||||
|
}
|
||||||
|
if (sdMutex != NULL) {
|
||||||
|
vSemaphoreDelete(sdMutex);
|
||||||
|
sdMutex = NULL;
|
||||||
|
}
|
||||||
|
if (rtcMutex != NULL) {
|
||||||
|
vSemaphoreDelete(rtcMutex);
|
||||||
|
rtcMutex = NULL;
|
||||||
|
}
|
||||||
|
if (canMutex != NULL) {
|
||||||
|
vSemaphoreDelete(canMutex);
|
||||||
|
canMutex = NULL;
|
||||||
|
}
|
||||||
|
}
|
||||||
42
task_config.h
Normal file
42
task_config.h
Normal file
@@ -0,0 +1,42 @@
|
|||||||
|
// task_config.h - FreeRTOS Task Structure for ESP32-S3 CAN FD Logger
|
||||||
|
|
||||||
|
#ifndef TASK_CONFIG_H
|
||||||
|
#define TASK_CONFIG_H
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "config.h"
|
||||||
|
#include "types.h"
|
||||||
|
|
||||||
|
#define CORE_0 0
|
||||||
|
#define CORE_1 1
|
||||||
|
|
||||||
|
#define QUEUE_TIMEOUT_MS 100
|
||||||
|
|
||||||
|
extern TaskHandle_t canRxTaskHandle;
|
||||||
|
extern TaskHandle_t sdWriteTaskHandle;
|
||||||
|
extern TaskHandle_t canTxTaskHandle;
|
||||||
|
extern TaskHandle_t wsTxTaskHandle;
|
||||||
|
extern TaskHandle_t webServerTaskHandle;
|
||||||
|
extern TaskHandle_t timeSyncTaskHandle;
|
||||||
|
|
||||||
|
extern QueueHandle_t canRxQueue;
|
||||||
|
extern QueueHandle_t canTxQueue;
|
||||||
|
extern QueueHandle_t graphQueue;
|
||||||
|
|
||||||
|
extern SemaphoreHandle_t configMutex;
|
||||||
|
extern SemaphoreHandle_t sdMutex;
|
||||||
|
extern SemaphoreHandle_t rtcMutex;
|
||||||
|
extern SemaphoreHandle_t canMutex;
|
||||||
|
|
||||||
|
void canRxTask(void *pvParameters);
|
||||||
|
void sdWriteTask(void *pvParameters);
|
||||||
|
void canTxTask(void *pvParameters);
|
||||||
|
void wsTxTask(void *pvParameters);
|
||||||
|
void webServerTask(void *pvParameters);
|
||||||
|
void timeSyncTask(void *pvParameters);
|
||||||
|
|
||||||
|
bool initFreeRTOSResources();
|
||||||
|
bool createAllTasks();
|
||||||
|
void deleteAllTasks();
|
||||||
|
|
||||||
|
#endif // TASK_CONFIG_H
|
||||||
285
test_handler.cpp
Normal file
285
test_handler.cpp
Normal file
@@ -0,0 +1,285 @@
|
|||||||
|
// test_handler.cpp - Hardware Test Handler Implementation
|
||||||
|
|
||||||
|
#include "test_handler.h"
|
||||||
|
#include "can_handler.h"
|
||||||
|
#include "task_config.h"
|
||||||
|
#include "psram_buffer.h"
|
||||||
|
|
||||||
|
TestConfig testConfig;
|
||||||
|
TestResult testResult;
|
||||||
|
static uint32_t expectedSequence = 0;
|
||||||
|
static uint32_t receivedSequence = 0;
|
||||||
|
static TaskHandle_t testTaskHandle = NULL;
|
||||||
|
|
||||||
|
void initTestHandler() {
|
||||||
|
testConfig.mode = TEST_MODE_IDLE;
|
||||||
|
testConfig.frameCount = 1000;
|
||||||
|
testConfig.intervalUs = 1000;
|
||||||
|
testConfig.canId = 0x100;
|
||||||
|
testConfig.dataLen = 8;
|
||||||
|
testConfig.useFD = true;
|
||||||
|
testConfig.running = false;
|
||||||
|
|
||||||
|
memset(&testResult, 0, sizeof(TestResult));
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t generateTestFrame(uint32_t sequence, CanFrame& frame) {
|
||||||
|
frame.timestamp = micros();
|
||||||
|
frame.id = testConfig.canId;
|
||||||
|
frame.len = testConfig.useFD ? (testConfig.dataLen > 8 ? testConfig.dataLen : 8) : 8;
|
||||||
|
frame.flags = testConfig.useFD ? 0x01 : 0x00;
|
||||||
|
|
||||||
|
frame.data[0] = (sequence >> 24) & 0xFF;
|
||||||
|
frame.data[1] = (sequence >> 16) & 0xFF;
|
||||||
|
frame.data[2] = (sequence >> 8) & 0xFF;
|
||||||
|
frame.data[3] = sequence & 0xFF;
|
||||||
|
frame.data[4] = 0xDE;
|
||||||
|
frame.data[5] = 0xAD;
|
||||||
|
frame.data[6] = 0xBE;
|
||||||
|
frame.data[7] = 0xEF;
|
||||||
|
|
||||||
|
for (int i = 8; i < frame.len && i < 64; i++) {
|
||||||
|
frame.data[i] = (uint8_t)(sequence + i);
|
||||||
|
}
|
||||||
|
|
||||||
|
return sequence;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool validateTestFrame(const CanFrame& frame, uint32_t& expectedSeq) {
|
||||||
|
if (frame.id != testConfig.canId) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t receivedSeq = ((uint32_t)frame.data[0] << 24) |
|
||||||
|
((uint32_t)frame.data[1] << 16) |
|
||||||
|
((uint32_t)frame.data[2] << 8) |
|
||||||
|
((uint32_t)frame.data[3]);
|
||||||
|
|
||||||
|
if (receivedSeq != expectedSeq) {
|
||||||
|
uint32_t lost = receivedSeq - expectedSeq;
|
||||||
|
testResult.framesLost += lost;
|
||||||
|
expectedSeq = receivedSeq + 1;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
expectedSeq++;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void testTxTask(void *pvParameters) {
|
||||||
|
Serial.println("Test TX Task started");
|
||||||
|
|
||||||
|
uint32_t sequence = 0;
|
||||||
|
testResult.startTime = millis();
|
||||||
|
testResult.framesSent = 0;
|
||||||
|
testResult.framesReceived = 0;
|
||||||
|
testResult.framesLost = 0;
|
||||||
|
testResult.errors = 0;
|
||||||
|
|
||||||
|
uint8_t originalMode = getCANMode();
|
||||||
|
setCANMode(2);
|
||||||
|
delay(100);
|
||||||
|
|
||||||
|
expectedSequence = 0;
|
||||||
|
|
||||||
|
while (testConfig.running && sequence < testConfig.frameCount) {
|
||||||
|
CanFrame frame;
|
||||||
|
generateTestFrame(sequence, frame);
|
||||||
|
|
||||||
|
if (sendCANFrame(frame.id, frame.data, frame.len, testConfig.useFD)) {
|
||||||
|
testResult.framesSent++;
|
||||||
|
sequence++;
|
||||||
|
} else {
|
||||||
|
testResult.errors++;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (testConfig.intervalUs > 0) {
|
||||||
|
delayMicroseconds(testConfig.intervalUs);
|
||||||
|
}
|
||||||
|
|
||||||
|
while (canController.available()) {
|
||||||
|
CANFDMessage rxMsg;
|
||||||
|
if (canController.receive(rxMsg)) {
|
||||||
|
CanFrame rxFrame;
|
||||||
|
rxFrame.id = rxMsg.id;
|
||||||
|
rxFrame.len = rxMsg.len;
|
||||||
|
memcpy(rxFrame.data, rxMsg.data, rxMsg.len);
|
||||||
|
|
||||||
|
if (rxFrame.id == testConfig.canId) {
|
||||||
|
if (validateTestFrame(rxFrame, expectedSequence)) {
|
||||||
|
testResult.framesReceived++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
delay(100);
|
||||||
|
|
||||||
|
while (canController.available()) {
|
||||||
|
CANFDMessage rxMsg;
|
||||||
|
if (canController.receive(rxMsg)) {
|
||||||
|
CanFrame rxFrame;
|
||||||
|
rxFrame.id = rxMsg.id;
|
||||||
|
rxFrame.len = rxMsg.len;
|
||||||
|
memcpy(rxFrame.data, rxMsg.data, rxMsg.len);
|
||||||
|
|
||||||
|
if (rxFrame.id == testConfig.canId) {
|
||||||
|
if (validateTestFrame(rxFrame, expectedSequence)) {
|
||||||
|
testResult.framesReceived++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
testResult.endTime = millis();
|
||||||
|
testResult.durationMs = testResult.endTime - testResult.startTime;
|
||||||
|
|
||||||
|
if (testResult.durationMs > 0) {
|
||||||
|
testResult.frameRate = (float)testResult.framesSent / ((float)testResult.durationMs / 1000.0f);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (testResult.framesSent > 0) {
|
||||||
|
testResult.lossRate = (float)testResult.framesLost / (float)testResult.framesSent * 100.0f;
|
||||||
|
}
|
||||||
|
|
||||||
|
testResult.passed = (testResult.framesLost == 0 && testResult.framesSent == testResult.framesReceived);
|
||||||
|
|
||||||
|
setCANMode(originalMode);
|
||||||
|
testConfig.running = false;
|
||||||
|
testConfig.mode = TEST_MODE_IDLE;
|
||||||
|
|
||||||
|
Serial.printf("Test completed: Sent=%d, Received=%d, Lost=%d, Rate=%.1f fps, Loss=%.2f%%\n",
|
||||||
|
testResult.framesSent, testResult.framesReceived, testResult.framesLost,
|
||||||
|
testResult.frameRate, testResult.lossRate);
|
||||||
|
|
||||||
|
vTaskDelete(NULL);
|
||||||
|
testTaskHandle = NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool startLoopbackTest(uint32_t frameCount, uint32_t intervalUs) {
|
||||||
|
if (testConfig.running) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
testConfig.mode = TEST_MODE_LOOPBACK;
|
||||||
|
testConfig.frameCount = frameCount;
|
||||||
|
testConfig.intervalUs = intervalUs;
|
||||||
|
testConfig.canId = 0x100;
|
||||||
|
testConfig.dataLen = 8;
|
||||||
|
testConfig.useFD = false;
|
||||||
|
testConfig.running = true;
|
||||||
|
|
||||||
|
Serial.printf("Starting loopback test: %d frames, %d us interval\n", frameCount, intervalUs);
|
||||||
|
|
||||||
|
xTaskCreatePinnedToCore(
|
||||||
|
testTxTask,
|
||||||
|
"TEST_TX",
|
||||||
|
4096,
|
||||||
|
NULL,
|
||||||
|
6,
|
||||||
|
&testTaskHandle,
|
||||||
|
0
|
||||||
|
);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool startStressTest(uint32_t frameCount, uint8_t dataLen, bool useFD) {
|
||||||
|
if (testConfig.running) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
testConfig.mode = TEST_MODE_STRESS;
|
||||||
|
testConfig.frameCount = frameCount;
|
||||||
|
testConfig.intervalUs = 0;
|
||||||
|
testConfig.canId = 0x200;
|
||||||
|
testConfig.dataLen = dataLen;
|
||||||
|
testConfig.useFD = useFD;
|
||||||
|
testConfig.running = true;
|
||||||
|
|
||||||
|
Serial.printf("Starting stress test: %d frames, %d bytes, FD=%s\n",
|
||||||
|
frameCount, dataLen, useFD ? "true" : "false");
|
||||||
|
|
||||||
|
xTaskCreatePinnedToCore(
|
||||||
|
testTxTask,
|
||||||
|
"TEST_TX",
|
||||||
|
4096,
|
||||||
|
NULL,
|
||||||
|
6,
|
||||||
|
&testTaskHandle,
|
||||||
|
0
|
||||||
|
);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool startSequenceTest(uint32_t frameCount, uint32_t canId) {
|
||||||
|
if (testConfig.running) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
testConfig.mode = TEST_MODE_SEQUENCE;
|
||||||
|
testConfig.frameCount = frameCount;
|
||||||
|
testConfig.intervalUs = 1000;
|
||||||
|
testConfig.canId = canId;
|
||||||
|
testConfig.dataLen = 64;
|
||||||
|
testConfig.useFD = true;
|
||||||
|
testConfig.running = true;
|
||||||
|
|
||||||
|
Serial.printf("Starting sequence test: %d frames, ID=0x%X\n", frameCount, canId);
|
||||||
|
|
||||||
|
xTaskCreatePinnedToCore(
|
||||||
|
testTxTask,
|
||||||
|
"TEST_TX",
|
||||||
|
4096,
|
||||||
|
NULL,
|
||||||
|
6,
|
||||||
|
&testTaskHandle,
|
||||||
|
0
|
||||||
|
);
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void stopTest() {
|
||||||
|
if (testConfig.running) {
|
||||||
|
testConfig.running = false;
|
||||||
|
if (testTaskHandle != NULL) {
|
||||||
|
vTaskDelay(pdMS_TO_TICKS(100));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void updateTest() {
|
||||||
|
}
|
||||||
|
|
||||||
|
bool isTestRunning() {
|
||||||
|
return testConfig.running;
|
||||||
|
}
|
||||||
|
|
||||||
|
TestMode getTestMode() {
|
||||||
|
return testConfig.mode;
|
||||||
|
}
|
||||||
|
|
||||||
|
TestResult getTestResult() {
|
||||||
|
return testResult;
|
||||||
|
}
|
||||||
|
|
||||||
|
void getTestResultJSON(char* buffer, size_t bufferSize) {
|
||||||
|
snprintf(buffer, bufferSize,
|
||||||
|
"{\"running\":%s,\"mode\":%d,\"result\":{"
|
||||||
|
"\"framesSent\":%d,\"framesReceived\":%d,\"framesLost\":%d,"
|
||||||
|
"\"errors\":%d,\"durationMs\":%d,\"frameRate\":%.1f,"
|
||||||
|
"\"lossRate\":%.2f,\"passed\":%s}}",
|
||||||
|
testConfig.running ? "true" : "false",
|
||||||
|
testConfig.mode,
|
||||||
|
testResult.framesSent,
|
||||||
|
testResult.framesReceived,
|
||||||
|
testResult.framesLost,
|
||||||
|
testResult.errors,
|
||||||
|
testResult.durationMs,
|
||||||
|
testResult.frameRate,
|
||||||
|
testResult.lossRate,
|
||||||
|
testResult.passed ? "true" : "false");
|
||||||
|
}
|
||||||
65
test_handler.h
Normal file
65
test_handler.h
Normal file
@@ -0,0 +1,65 @@
|
|||||||
|
// test_handler.h - Hardware Test Handler for CAN FD Logger
|
||||||
|
|
||||||
|
#ifndef TEST_HANDLER_H
|
||||||
|
#define TEST_HANDLER_H
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "types.h"
|
||||||
|
|
||||||
|
#define TEST_MAX_FRAMES 10000
|
||||||
|
#define TEST_DEFAULT_INTERVAL 1
|
||||||
|
|
||||||
|
enum TestMode {
|
||||||
|
TEST_MODE_IDLE = 0,
|
||||||
|
TEST_MODE_LOOPBACK,
|
||||||
|
TEST_MODE_STRESS,
|
||||||
|
TEST_MODE_SEQUENCE
|
||||||
|
};
|
||||||
|
|
||||||
|
struct TestConfig {
|
||||||
|
TestMode mode;
|
||||||
|
uint32_t frameCount;
|
||||||
|
uint32_t intervalUs;
|
||||||
|
uint32_t canId;
|
||||||
|
uint8_t dataLen;
|
||||||
|
bool useFD;
|
||||||
|
bool running;
|
||||||
|
};
|
||||||
|
|
||||||
|
struct TestResult {
|
||||||
|
uint32_t framesSent;
|
||||||
|
uint32_t framesReceived;
|
||||||
|
uint32_t framesLost;
|
||||||
|
uint32_t errors;
|
||||||
|
uint32_t startTime;
|
||||||
|
uint32_t endTime;
|
||||||
|
uint32_t durationMs;
|
||||||
|
float frameRate;
|
||||||
|
float lossRate;
|
||||||
|
bool passed;
|
||||||
|
};
|
||||||
|
|
||||||
|
extern TestConfig testConfig;
|
||||||
|
extern TestResult testResult;
|
||||||
|
|
||||||
|
void initTestHandler();
|
||||||
|
|
||||||
|
bool startLoopbackTest(uint32_t frameCount, uint32_t intervalUs);
|
||||||
|
bool startStressTest(uint32_t frameCount, uint8_t dataLen, bool useFD);
|
||||||
|
bool startSequenceTest(uint32_t frameCount, uint32_t canId);
|
||||||
|
|
||||||
|
void stopTest();
|
||||||
|
void updateTest();
|
||||||
|
|
||||||
|
bool isTestRunning();
|
||||||
|
TestMode getTestMode();
|
||||||
|
TestResult getTestResult();
|
||||||
|
|
||||||
|
void getTestResultJSON(char* buffer, size_t bufferSize);
|
||||||
|
|
||||||
|
void testTxTask(void *pvParameters);
|
||||||
|
|
||||||
|
uint32_t generateTestFrame(uint32_t sequence, CanFrame& frame);
|
||||||
|
bool validateTestFrame(const CanFrame& frame, uint32_t& expectedSeq);
|
||||||
|
|
||||||
|
#endif // TEST_HANDLER_H
|
||||||
30
types.h
Normal file
30
types.h
Normal file
@@ -0,0 +1,30 @@
|
|||||||
|
// types.h - Common data structures for ESP32-S3 CAN FD Logger
|
||||||
|
|
||||||
|
#ifndef TYPES_H
|
||||||
|
#define TYPES_H
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
struct CanFrame {
|
||||||
|
uint64_t timestamp;
|
||||||
|
uint32_t id;
|
||||||
|
uint8_t len;
|
||||||
|
uint8_t flags;
|
||||||
|
uint8_t data[64];
|
||||||
|
};
|
||||||
|
|
||||||
|
struct CanTxRequest {
|
||||||
|
uint32_t id;
|
||||||
|
uint8_t len;
|
||||||
|
uint8_t data[64];
|
||||||
|
uint32_t delay_ms;
|
||||||
|
uint32_t repeat_count;
|
||||||
|
};
|
||||||
|
|
||||||
|
struct GraphSignal {
|
||||||
|
char signal_id[32];
|
||||||
|
float value;
|
||||||
|
uint32_t timestamp;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // TYPES_H
|
||||||
337
web_can.h
Normal file
337
web_can.h
Normal file
@@ -0,0 +1,337 @@
|
|||||||
|
#ifndef WEB_CAN_H
|
||||||
|
#define WEB_CAN_H
|
||||||
|
|
||||||
|
const char HTML_CAN[] = R"rawliteral(
|
||||||
|
<!DOCTYPE html>
|
||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta charset="UTF-8">
|
||||||
|
<meta name="viewport" content="width=device-width, initial-scale=1.0">
|
||||||
|
<title>CAN Transmit - ESP32 Logger</title>
|
||||||
|
<style>
|
||||||
|
* { margin: 0; padding: 0; box-sizing: border-box; }
|
||||||
|
body {
|
||||||
|
font-family: -apple-system, BlinkMacSystemFont, 'Segoe UI', Roboto, sans-serif;
|
||||||
|
background: #1a1a2e;
|
||||||
|
color: #eee;
|
||||||
|
line-height: 1.6;
|
||||||
|
}
|
||||||
|
.header {
|
||||||
|
background: #16213e;
|
||||||
|
padding: 1rem;
|
||||||
|
text-align: center;
|
||||||
|
border-bottom: 2px solid #e94560;
|
||||||
|
}
|
||||||
|
.header h1 { color: #e94560; font-size: 1.5rem; }
|
||||||
|
.nav {
|
||||||
|
background: #0f3460;
|
||||||
|
padding: 0.5rem;
|
||||||
|
display: flex;
|
||||||
|
justify-content: center;
|
||||||
|
flex-wrap: wrap;
|
||||||
|
gap: 0.5rem;
|
||||||
|
}
|
||||||
|
.nav a {
|
||||||
|
color: #fff;
|
||||||
|
text-decoration: none;
|
||||||
|
padding: 0.5rem 1rem;
|
||||||
|
border-radius: 4px;
|
||||||
|
transition: background 0.3s;
|
||||||
|
}
|
||||||
|
.nav a:hover, .nav a.active { background: #e94560; }
|
||||||
|
.container {
|
||||||
|
max-width: 800px;
|
||||||
|
margin: 0 auto;
|
||||||
|
padding: 2rem;
|
||||||
|
}
|
||||||
|
.form-card {
|
||||||
|
background: #16213e;
|
||||||
|
padding: 2rem;
|
||||||
|
border-radius: 8px;
|
||||||
|
margin-bottom: 1rem;
|
||||||
|
}
|
||||||
|
.form-card h2 {
|
||||||
|
color: #e94560;
|
||||||
|
margin-bottom: 1.5rem;
|
||||||
|
}
|
||||||
|
.form-group {
|
||||||
|
margin-bottom: 1.5rem;
|
||||||
|
}
|
||||||
|
.form-group label {
|
||||||
|
display: block;
|
||||||
|
margin-bottom: 0.5rem;
|
||||||
|
color: #00d9ff;
|
||||||
|
}
|
||||||
|
.form-group input, .form-group select {
|
||||||
|
width: 100%;
|
||||||
|
padding: 0.75rem;
|
||||||
|
background: #0f3460;
|
||||||
|
border: 1px solid #e94560;
|
||||||
|
color: #fff;
|
||||||
|
border-radius: 4px;
|
||||||
|
font-size: 1rem;
|
||||||
|
}
|
||||||
|
.form-group input:focus {
|
||||||
|
outline: none;
|
||||||
|
border-color: #00d9ff;
|
||||||
|
}
|
||||||
|
.data-bytes {
|
||||||
|
display: grid;
|
||||||
|
grid-template-columns: repeat(8, 1fr);
|
||||||
|
gap: 0.5rem;
|
||||||
|
}
|
||||||
|
.data-bytes input {
|
||||||
|
text-align: center;
|
||||||
|
padding: 0.5rem;
|
||||||
|
}
|
||||||
|
.btn {
|
||||||
|
background: #e94560;
|
||||||
|
color: #fff;
|
||||||
|
border: none;
|
||||||
|
padding: 1rem 2rem;
|
||||||
|
font-size: 1rem;
|
||||||
|
border-radius: 4px;
|
||||||
|
cursor: pointer;
|
||||||
|
transition: background 0.3s;
|
||||||
|
width: 100%;
|
||||||
|
}
|
||||||
|
.btn:hover { background: #ff6b6b; }
|
||||||
|
.btn-green { background: #00d9ff; }
|
||||||
|
.btn-green:hover { background: #00b8d4; }
|
||||||
|
.row {
|
||||||
|
display: grid;
|
||||||
|
grid-template-columns: 1fr 1fr;
|
||||||
|
gap: 1rem;
|
||||||
|
}
|
||||||
|
.info-text {
|
||||||
|
color: #666;
|
||||||
|
font-size: 0.875rem;
|
||||||
|
margin-top: 0.25rem;
|
||||||
|
}
|
||||||
|
</style>
|
||||||
|
</head>
|
||||||
|
<body>
|
||||||
|
<div class="header">
|
||||||
|
<h1>CAN Transmit</h1>
|
||||||
|
</div>
|
||||||
|
<nav class="nav">
|
||||||
|
<a href="/">Dashboard</a>
|
||||||
|
<a href="/graph">Graph</a>
|
||||||
|
<a href="/files">Files</a>
|
||||||
|
<a href="/can" class="active">CAN Transmit</a>
|
||||||
|
<a href="/settings">Settings</a>
|
||||||
|
</nav>
|
||||||
|
<div class="container">
|
||||||
|
<div class="form-card">
|
||||||
|
<h2>Transmit CAN Frame</h2>
|
||||||
|
<form id="canForm" onsubmit="sendFrame(event)">
|
||||||
|
<div class="form-group">
|
||||||
|
<label>CAN ID (Hex)</label>
|
||||||
|
<input type="text" id="canId" placeholder="0x100" value="0x100">
|
||||||
|
<div class="info-text">Example: 0x100, 0x7DF, 0x18FF1234</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="row">
|
||||||
|
<div class="form-group">
|
||||||
|
<label>Frame Type</label>
|
||||||
|
<select id="frameType" onchange="updateDataLengthOptions()">
|
||||||
|
<option value="standard">Classic CAN (11-bit, 8 bytes max)</option>
|
||||||
|
<option value="extended">Classic CAN Extended (29-bit, 8 bytes max)</option>
|
||||||
|
<option value="fd">CAN FD (up to 64 bytes)</option>
|
||||||
|
</select>
|
||||||
|
</div>
|
||||||
|
<div class="form-group">
|
||||||
|
<label>Data Length</label>
|
||||||
|
<select id="dataLength" onchange="updateDataFields()">
|
||||||
|
<option value="0">0 bytes</option>
|
||||||
|
<option value="1">1 byte</option>
|
||||||
|
<option value="2">2 bytes</option>
|
||||||
|
<option value="4">4 bytes</option>
|
||||||
|
<option value="8" selected>8 bytes</option>
|
||||||
|
</select>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="form-group">
|
||||||
|
<label>Data Bytes (Hex)</label>
|
||||||
|
<div class="data-bytes" id="dataBytes">
|
||||||
|
<input type="text" maxlength="2" value="00">
|
||||||
|
<input type="text" maxlength="2" value="00">
|
||||||
|
<input type="text" maxlength="2" value="00">
|
||||||
|
<input type="text" maxlength="2" value="00">
|
||||||
|
<input type="text" maxlength="2" value="00">
|
||||||
|
<input type="text" maxlength="2" value="00">
|
||||||
|
<input type="text" maxlength="2" value="00">
|
||||||
|
<input type="text" maxlength="2" value="00">
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="row">
|
||||||
|
<div class="form-group">
|
||||||
|
<label>Repeat Count</label>
|
||||||
|
<input type="number" id="repeatCount" value="1" min="1" max="10000">
|
||||||
|
<div class="info-text">1-10000 (1 = single)</div>
|
||||||
|
</div>
|
||||||
|
<div class="form-group">
|
||||||
|
<label>Delay (ms)</label>
|
||||||
|
<input type="number" id="delayMs" value="100" min="0" max="10000">
|
||||||
|
<div class="info-text">Delay between repeats</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<button type="submit" class="btn">Send Frame</button>
|
||||||
|
</form>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="form-card">
|
||||||
|
<h2>Quick Send</h2>
|
||||||
|
<div style="display: flex; gap: 1rem; flex-wrap: wrap;">
|
||||||
|
<button class="btn btn-green" onclick="quickSend('0x100', [0x01, 0x02, 0x03, 0x04])">
|
||||||
|
Test Frame 1
|
||||||
|
</button>
|
||||||
|
<button class="btn btn-green" onclick="quickSend('0x200', [0xAA, 0xBB, 0xCC, 0xDD])">
|
||||||
|
Test Frame 2
|
||||||
|
</button>
|
||||||
|
<button class="btn btn-green" onclick="quickSend('0x7DF', [0x02, 0x01, 0x0C, 0x00])">
|
||||||
|
OBD2 RPM
|
||||||
|
</button>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<script>
|
||||||
|
function updateDataLengthOptions() {
|
||||||
|
const frameType = document.getElementById('frameType').value;
|
||||||
|
const dataLengthSelect = document.getElementById('dataLength');
|
||||||
|
const currentValue = dataLengthSelect.value;
|
||||||
|
|
||||||
|
dataLengthSelect.innerHTML = '';
|
||||||
|
|
||||||
|
const classicOptions = [
|
||||||
|
{value: '0', text: '0 bytes'},
|
||||||
|
{value: '1', text: '1 byte'},
|
||||||
|
{value: '2', text: '2 bytes'},
|
||||||
|
{value: '3', text: '3 bytes'},
|
||||||
|
{value: '4', text: '4 bytes'},
|
||||||
|
{value: '5', text: '5 bytes'},
|
||||||
|
{value: '6', text: '6 bytes'},
|
||||||
|
{value: '7', text: '7 bytes'},
|
||||||
|
{value: '8', text: '8 bytes'}
|
||||||
|
];
|
||||||
|
|
||||||
|
const fdOptions = [
|
||||||
|
{value: '0', text: '0 bytes'},
|
||||||
|
{value: '8', text: '8 bytes'},
|
||||||
|
{value: '12', text: '12 bytes'},
|
||||||
|
{value: '16', text: '16 bytes'},
|
||||||
|
{value: '20', text: '20 bytes'},
|
||||||
|
{value: '24', text: '24 bytes'},
|
||||||
|
{value: '32', text: '32 bytes'},
|
||||||
|
{value: '48', text: '48 bytes'},
|
||||||
|
{value: '64', text: '64 bytes'}
|
||||||
|
];
|
||||||
|
|
||||||
|
const options = frameType === 'fd' ? fdOptions : classicOptions;
|
||||||
|
|
||||||
|
options.forEach(opt => {
|
||||||
|
const option = document.createElement('option');
|
||||||
|
option.value = opt.value;
|
||||||
|
option.textContent = opt.text;
|
||||||
|
if (opt.value === currentValue || (opt.value === '8' && !options.find(o => o.value === currentValue))) {
|
||||||
|
option.selected = true;
|
||||||
|
}
|
||||||
|
dataLengthSelect.appendChild(option);
|
||||||
|
});
|
||||||
|
|
||||||
|
updateDataFields();
|
||||||
|
}
|
||||||
|
|
||||||
|
function updateDataFields() {
|
||||||
|
const len = parseInt(document.getElementById('dataLength').value);
|
||||||
|
const container = document.getElementById('dataBytes');
|
||||||
|
container.innerHTML = '';
|
||||||
|
|
||||||
|
const displayCount = len <= 8 ? len : 8;
|
||||||
|
for (let i = 0; i < displayCount; i++) {
|
||||||
|
const input = document.createElement('input');
|
||||||
|
input.type = 'text';
|
||||||
|
input.maxLength = 2;
|
||||||
|
input.value = '00';
|
||||||
|
container.appendChild(input);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (len > 8) {
|
||||||
|
const info = document.createElement('div');
|
||||||
|
info.style.gridColumn = '1 / -1';
|
||||||
|
info.style.fontSize = '0.75rem';
|
||||||
|
info.style.color = '#aaa';
|
||||||
|
info.textContent = `Showing first 8 of ${len} bytes`;
|
||||||
|
container.appendChild(info);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
function sendFrame(event) {
|
||||||
|
event.preventDefault();
|
||||||
|
|
||||||
|
const canId = document.getElementById('canId').value;
|
||||||
|
const frameType = document.getElementById('frameType').value;
|
||||||
|
const dataLength = parseInt(document.getElementById('dataLength').value);
|
||||||
|
const repeatCount = parseInt(document.getElementById('repeatCount').value);
|
||||||
|
const delayMs = parseInt(document.getElementById('delayMs').value);
|
||||||
|
|
||||||
|
const dataBytes = [];
|
||||||
|
const inputs = document.querySelectorAll('#dataBytes input');
|
||||||
|
inputs.forEach(input => {
|
||||||
|
if (input.type === 'text') {
|
||||||
|
dataBytes.push(parseInt(input.value, 16) || 0);
|
||||||
|
}
|
||||||
|
});
|
||||||
|
|
||||||
|
while (dataBytes.length < dataLength) {
|
||||||
|
dataBytes.push(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
const payload = {
|
||||||
|
id: canId,
|
||||||
|
type: frameType,
|
||||||
|
length: dataLength,
|
||||||
|
data: dataBytes.slice(0, dataLength),
|
||||||
|
repeat: repeatCount,
|
||||||
|
delay: delayMs,
|
||||||
|
isFD: frameType === 'fd'
|
||||||
|
};
|
||||||
|
|
||||||
|
fetch('/api/can/send', {
|
||||||
|
method: 'POST',
|
||||||
|
headers: {'Content-Type': 'application/json'},
|
||||||
|
body: JSON.stringify(payload)
|
||||||
|
})
|
||||||
|
.then(r => r.json())
|
||||||
|
.then(data => {
|
||||||
|
alert('Frame sent successfully!');
|
||||||
|
})
|
||||||
|
.catch(err => {
|
||||||
|
alert('Error: ' + err.message);
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
function quickSend(id, data) {
|
||||||
|
document.getElementById('canId').value = id;
|
||||||
|
document.getElementById('frameType').value = 'standard';
|
||||||
|
updateDataLengthOptions();
|
||||||
|
document.getElementById('dataLength').value = data.length;
|
||||||
|
updateDataFields();
|
||||||
|
|
||||||
|
const inputs = document.querySelectorAll('#dataBytes input');
|
||||||
|
data.forEach((byte, i) => {
|
||||||
|
if (inputs[i]) inputs[i].value = byte.toString(16).padStart(2, '0');
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
updateDataLengthOptions();
|
||||||
|
</script>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
|
)rawliteral";
|
||||||
|
|
||||||
|
#endif // WEB_CAN_H
|
||||||
314
web_files.h
Normal file
314
web_files.h
Normal file
@@ -0,0 +1,314 @@
|
|||||||
|
#ifndef WEB_FILES_H
|
||||||
|
#define WEB_FILES_H
|
||||||
|
|
||||||
|
const char HTML_FILES[] = R"rawliteral(
|
||||||
|
<!DOCTYPE html>
|
||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta charset="UTF-8">
|
||||||
|
<meta name="viewport" content="width=device-width, initial-scale=1.0">
|
||||||
|
<title>File Manager - ESP32 Logger</title>
|
||||||
|
<style>
|
||||||
|
* { margin: 0; padding: 0; box-sizing: border-box; }
|
||||||
|
body {
|
||||||
|
font-family: -apple-system, BlinkMacSystemFont, 'Segoe UI', Roboto, sans-serif;
|
||||||
|
background: #1a1a2e;
|
||||||
|
color: #eee;
|
||||||
|
line-height: 1.6;
|
||||||
|
}
|
||||||
|
.header {
|
||||||
|
background: #16213e;
|
||||||
|
padding: 1rem;
|
||||||
|
text-align: center;
|
||||||
|
border-bottom: 2px solid #e94560;
|
||||||
|
}
|
||||||
|
.header h1 { color: #e94560; font-size: 1.5rem; }
|
||||||
|
.nav {
|
||||||
|
background: #0f3460;
|
||||||
|
padding: 0.5rem;
|
||||||
|
display: flex;
|
||||||
|
justify-content: center;
|
||||||
|
flex-wrap: wrap;
|
||||||
|
gap: 0.5rem;
|
||||||
|
}
|
||||||
|
.nav a {
|
||||||
|
color: #fff;
|
||||||
|
text-decoration: none;
|
||||||
|
padding: 0.5rem 1rem;
|
||||||
|
border-radius: 4px;
|
||||||
|
transition: background 0.3s;
|
||||||
|
}
|
||||||
|
.nav a:hover, .nav a.active { background: #e94560; }
|
||||||
|
.container {
|
||||||
|
max-width: 1200px;
|
||||||
|
margin: 0 auto;
|
||||||
|
padding: 2rem;
|
||||||
|
}
|
||||||
|
.toolbar {
|
||||||
|
background: #16213e;
|
||||||
|
padding: 1rem;
|
||||||
|
border-radius: 8px;
|
||||||
|
margin-bottom: 1rem;
|
||||||
|
display: flex;
|
||||||
|
gap: 1rem;
|
||||||
|
flex-wrap: wrap;
|
||||||
|
}
|
||||||
|
.btn {
|
||||||
|
background: #e94560;
|
||||||
|
color: #fff;
|
||||||
|
border: none;
|
||||||
|
padding: 0.5rem 1rem;
|
||||||
|
border-radius: 4px;
|
||||||
|
cursor: pointer;
|
||||||
|
transition: background 0.3s;
|
||||||
|
}
|
||||||
|
.btn:hover { background: #ff6b6b; }
|
||||||
|
.btn:disabled { background: #666; cursor: not-allowed; }
|
||||||
|
.file-list {
|
||||||
|
background: #16213e;
|
||||||
|
border-radius: 8px;
|
||||||
|
overflow: hidden;
|
||||||
|
}
|
||||||
|
.file-header {
|
||||||
|
display: grid;
|
||||||
|
grid-template-columns: 40px 2fr 1fr 1fr 120px;
|
||||||
|
padding: 1rem;
|
||||||
|
background: #0f3460;
|
||||||
|
font-weight: bold;
|
||||||
|
}
|
||||||
|
.file-item {
|
||||||
|
display: grid;
|
||||||
|
grid-template-columns: 40px 2fr 1fr 1fr 120px;
|
||||||
|
padding: 1rem;
|
||||||
|
border-bottom: 1px solid #0f3460;
|
||||||
|
align-items: center;
|
||||||
|
}
|
||||||
|
.file-item:hover { background: #1a1a2e; }
|
||||||
|
.file-item:last-child { border-bottom: none; }
|
||||||
|
.checkbox {
|
||||||
|
width: 20px;
|
||||||
|
height: 20px;
|
||||||
|
cursor: pointer;
|
||||||
|
}
|
||||||
|
.file-name { color: #00d9ff; }
|
||||||
|
.file-size { color: #aaa; }
|
||||||
|
.file-date { color: #aaa; }
|
||||||
|
.file-actions {
|
||||||
|
display: flex;
|
||||||
|
gap: 0.5rem;
|
||||||
|
}
|
||||||
|
.btn-small {
|
||||||
|
padding: 0.25rem 0.5rem;
|
||||||
|
font-size: 0.875rem;
|
||||||
|
}
|
||||||
|
.btn-blue { background: #3498db; }
|
||||||
|
.btn-red { background: #e74c3c; }
|
||||||
|
.empty-state {
|
||||||
|
text-align: center;
|
||||||
|
padding: 3rem;
|
||||||
|
color: #666;
|
||||||
|
}
|
||||||
|
.modal {
|
||||||
|
display: none;
|
||||||
|
position: fixed;
|
||||||
|
top: 0;
|
||||||
|
left: 0;
|
||||||
|
width: 100%;
|
||||||
|
height: 100%;
|
||||||
|
background: rgba(0,0,0,0.8);
|
||||||
|
justify-content: center;
|
||||||
|
align-items: center;
|
||||||
|
z-index: 1000;
|
||||||
|
}
|
||||||
|
.modal-content {
|
||||||
|
background: #16213e;
|
||||||
|
padding: 2rem;
|
||||||
|
border-radius: 8px;
|
||||||
|
max-width: 500px;
|
||||||
|
width: 90%;
|
||||||
|
}
|
||||||
|
.modal h3 { margin-bottom: 1rem; color: #e94560; }
|
||||||
|
.form-group { margin-bottom: 1rem; }
|
||||||
|
.form-group label { display: block; margin-bottom: 0.5rem; }
|
||||||
|
.form-group input, .form-group textarea {
|
||||||
|
width: 100%;
|
||||||
|
padding: 0.5rem;
|
||||||
|
background: #0f3460;
|
||||||
|
border: 1px solid #e94560;
|
||||||
|
color: #fff;
|
||||||
|
border-radius: 4px;
|
||||||
|
}
|
||||||
|
.modal-actions {
|
||||||
|
display: flex;
|
||||||
|
gap: 1rem;
|
||||||
|
justify-content: flex-end;
|
||||||
|
margin-top: 1rem;
|
||||||
|
}
|
||||||
|
</style>
|
||||||
|
</head>
|
||||||
|
<body>
|
||||||
|
<div class="header">
|
||||||
|
<h1>File Manager</h1>
|
||||||
|
</div>
|
||||||
|
<nav class="nav">
|
||||||
|
<a href="/">Dashboard</a>
|
||||||
|
<a href="/graph">Graph</a>
|
||||||
|
<a href="/files" class="active">Files</a>
|
||||||
|
<a href="/can">CAN Transmit</a>
|
||||||
|
<a href="/settings">Settings</a>
|
||||||
|
</nav>
|
||||||
|
<div class="container">
|
||||||
|
<div class="toolbar">
|
||||||
|
<button class="btn" id="btnSelectAll" onclick="toggleSelectAll()">Select All</button>
|
||||||
|
<button class="btn" onclick="downloadSelected()" id="btnDownload">Download Selected</button>
|
||||||
|
<button class="btn btn-red" onclick="deleteSelected()" id="btnDelete">Delete Selected</button>
|
||||||
|
<button class="btn" onclick="refreshFiles()">Refresh</button>
|
||||||
|
</div>
|
||||||
|
<div class="file-list" id="fileList">
|
||||||
|
<div class="file-header">
|
||||||
|
<input type="checkbox" class="checkbox" onchange="toggleSelectAll()">
|
||||||
|
<div>Name</div>
|
||||||
|
<div>Size</div>
|
||||||
|
<div>Date</div>
|
||||||
|
<div>Actions</div>
|
||||||
|
</div>
|
||||||
|
<div id="fileItems"></div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="modal" id="commentModal">
|
||||||
|
<div class="modal-content">
|
||||||
|
<h3>Add Comment</h3>
|
||||||
|
<div class="form-group">
|
||||||
|
<label>Comment:</label>
|
||||||
|
<textarea id="commentText" rows="3"></textarea>
|
||||||
|
</div>
|
||||||
|
<div class="modal-actions">
|
||||||
|
<button class="btn" onclick="closeModal()">Cancel</button>
|
||||||
|
<button class="btn btn-blue" onclick="saveComment()">Save</button>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<script>
|
||||||
|
let files = [];
|
||||||
|
let selectedFiles = new Set();
|
||||||
|
let currentCommentFile = null;
|
||||||
|
|
||||||
|
function loadFiles() {
|
||||||
|
fetch('/api/files')
|
||||||
|
.then(r => r.json())
|
||||||
|
.then(data => {
|
||||||
|
files = data;
|
||||||
|
renderFiles();
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
function renderFiles() {
|
||||||
|
const container = document.getElementById('fileItems');
|
||||||
|
|
||||||
|
if (files.length === 0) {
|
||||||
|
container.innerHTML = '<div class="empty-state">No log files found</div>';
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
container.innerHTML = files.map(file => `
|
||||||
|
<div class="file-item">
|
||||||
|
<input type="checkbox" class="checkbox"
|
||||||
|
${selectedFiles.has(file.name) ? 'checked' : ''}
|
||||||
|
onchange="toggleFile('${file.name}')">
|
||||||
|
<div class="file-name">${file.name}</div>
|
||||||
|
<div class="file-size">${formatSize(file.size)}</div>
|
||||||
|
<div class="file-date">${file.date}</div>
|
||||||
|
<div class="file-actions">
|
||||||
|
<button class="btn btn-small btn-blue" onclick="downloadFile('${file.name}')">Download</button>
|
||||||
|
<button class="btn btn-small" onclick="showCommentModal('${file.name}')">Comment</button>
|
||||||
|
<button class="btn btn-small btn-red" onclick="deleteFile('${file.name}')">Delete</button>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
`).join('');
|
||||||
|
}
|
||||||
|
|
||||||
|
function formatSize(bytes) {
|
||||||
|
if (bytes < 1024) return bytes + ' B';
|
||||||
|
if (bytes < 1024*1024) return (bytes/1024).toFixed(1) + ' KB';
|
||||||
|
return (bytes/(1024*1024)).toFixed(1) + ' MB';
|
||||||
|
}
|
||||||
|
|
||||||
|
function toggleFile(name) {
|
||||||
|
if (selectedFiles.has(name)) {
|
||||||
|
selectedFiles.delete(name);
|
||||||
|
} else {
|
||||||
|
selectedFiles.add(name);
|
||||||
|
}
|
||||||
|
updateToolbar();
|
||||||
|
}
|
||||||
|
|
||||||
|
function toggleSelectAll() {
|
||||||
|
if (selectedFiles.size === files.length) {
|
||||||
|
selectedFiles.clear();
|
||||||
|
} else {
|
||||||
|
files.forEach(f => selectedFiles.add(f.name));
|
||||||
|
}
|
||||||
|
renderFiles();
|
||||||
|
updateToolbar();
|
||||||
|
}
|
||||||
|
|
||||||
|
function updateToolbar() {
|
||||||
|
const hasSelection = selectedFiles.size > 0;
|
||||||
|
document.getElementById('btnDownload').disabled = !hasSelection;
|
||||||
|
document.getElementById('btnDelete').disabled = !hasSelection;
|
||||||
|
}
|
||||||
|
|
||||||
|
function downloadFile(name) {
|
||||||
|
window.location.href = '/api/files/download?name=' + encodeURIComponent(name);
|
||||||
|
}
|
||||||
|
|
||||||
|
function downloadSelected() {
|
||||||
|
selectedFiles.forEach(name => downloadFile(name));
|
||||||
|
}
|
||||||
|
|
||||||
|
function deleteFile(name) {
|
||||||
|
if (!confirm('Delete ' + name + '?')) return;
|
||||||
|
|
||||||
|
fetch('/api/files/delete?name=' + encodeURIComponent(name), {method: 'DELETE'})
|
||||||
|
.then(() => loadFiles());
|
||||||
|
}
|
||||||
|
|
||||||
|
function deleteSelected() {
|
||||||
|
if (!confirm('Delete ' + selectedFiles.size + ' files?')) return;
|
||||||
|
|
||||||
|
selectedFiles.forEach(name => {
|
||||||
|
fetch('/api/files/delete?name=' + encodeURIComponent(name), {method: 'DELETE'});
|
||||||
|
});
|
||||||
|
selectedFiles.clear();
|
||||||
|
setTimeout(loadFiles, 500);
|
||||||
|
}
|
||||||
|
|
||||||
|
function showCommentModal(name) {
|
||||||
|
currentCommentFile = name;
|
||||||
|
document.getElementById('commentModal').style.display = 'flex';
|
||||||
|
}
|
||||||
|
|
||||||
|
function closeModal() {
|
||||||
|
document.getElementById('commentModal').style.display = 'none';
|
||||||
|
currentCommentFile = null;
|
||||||
|
}
|
||||||
|
|
||||||
|
function saveComment() {
|
||||||
|
const comment = document.getElementById('commentText').value;
|
||||||
|
// TODO: Save comment
|
||||||
|
closeModal();
|
||||||
|
}
|
||||||
|
|
||||||
|
function refreshFiles() {
|
||||||
|
loadFiles();
|
||||||
|
}
|
||||||
|
|
||||||
|
loadFiles();
|
||||||
|
</script>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
|
)rawliteral";
|
||||||
|
|
||||||
|
#endif // WEB_FILES_H
|
||||||
247
web_graph.h
Normal file
247
web_graph.h
Normal file
@@ -0,0 +1,247 @@
|
|||||||
|
#ifndef WEB_GRAPH_H
|
||||||
|
#define WEB_GRAPH_H
|
||||||
|
|
||||||
|
const char HTML_GRAPH[] = R"rawliteral(
|
||||||
|
<!DOCTYPE html>
|
||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta charset="UTF-8">
|
||||||
|
<meta name="viewport" content="width=device-width, initial-scale=1.0">
|
||||||
|
<title>CAN FD Graph - ESP32 Logger</title>
|
||||||
|
<script src="https://unpkg.com/uplot@1.6.24/dist/uPlot.iife.min.js"></script>
|
||||||
|
<link rel="stylesheet" href="https://unpkg.com/uplot@1.6.24/dist/uPlot.min.css">
|
||||||
|
<style>
|
||||||
|
* { margin: 0; padding: 0; box-sizing: border-box; }
|
||||||
|
body {
|
||||||
|
font-family: -apple-system, BlinkMacSystemFont, 'Segoe UI', Roboto, sans-serif;
|
||||||
|
background: #1a1a2e;
|
||||||
|
color: #eee;
|
||||||
|
line-height: 1.6;
|
||||||
|
}
|
||||||
|
.header {
|
||||||
|
background: #16213e;
|
||||||
|
padding: 1rem;
|
||||||
|
text-align: center;
|
||||||
|
border-bottom: 2px solid #e94560;
|
||||||
|
}
|
||||||
|
.header h1 { color: #e94560; font-size: 1.5rem; }
|
||||||
|
.nav {
|
||||||
|
background: #0f3460;
|
||||||
|
padding: 0.5rem;
|
||||||
|
display: flex;
|
||||||
|
justify-content: center;
|
||||||
|
flex-wrap: wrap;
|
||||||
|
gap: 0.5rem;
|
||||||
|
}
|
||||||
|
.nav a {
|
||||||
|
color: #fff;
|
||||||
|
text-decoration: none;
|
||||||
|
padding: 0.5rem 1rem;
|
||||||
|
border-radius: 4px;
|
||||||
|
transition: background 0.3s;
|
||||||
|
}
|
||||||
|
.nav a:hover, .nav a.active { background: #e94560; }
|
||||||
|
.container {
|
||||||
|
max-width: 1400px;
|
||||||
|
margin: 0 auto;
|
||||||
|
padding: 1rem;
|
||||||
|
}
|
||||||
|
.graph-container {
|
||||||
|
background: #16213e;
|
||||||
|
padding: 1rem;
|
||||||
|
border-radius: 8px;
|
||||||
|
margin-bottom: 1rem;
|
||||||
|
}
|
||||||
|
.controls {
|
||||||
|
background: #16213e;
|
||||||
|
padding: 1rem;
|
||||||
|
border-radius: 8px;
|
||||||
|
margin-bottom: 1rem;
|
||||||
|
display: flex;
|
||||||
|
gap: 1rem;
|
||||||
|
flex-wrap: wrap;
|
||||||
|
align-items: center;
|
||||||
|
}
|
||||||
|
.signal-list {
|
||||||
|
display: flex;
|
||||||
|
gap: 1rem;
|
||||||
|
flex-wrap: wrap;
|
||||||
|
}
|
||||||
|
.signal-item {
|
||||||
|
display: flex;
|
||||||
|
align-items: center;
|
||||||
|
gap: 0.5rem;
|
||||||
|
}
|
||||||
|
.signal-color {
|
||||||
|
width: 16px;
|
||||||
|
height: 16px;
|
||||||
|
border-radius: 50%;
|
||||||
|
}
|
||||||
|
.btn {
|
||||||
|
background: #e94560;
|
||||||
|
color: #fff;
|
||||||
|
border: none;
|
||||||
|
padding: 0.5rem 1rem;
|
||||||
|
border-radius: 4px;
|
||||||
|
cursor: pointer;
|
||||||
|
}
|
||||||
|
.btn:hover { background: #ff6b6b; }
|
||||||
|
#chart { margin-top: 1rem; }
|
||||||
|
.uplot {
|
||||||
|
background: #0f3460;
|
||||||
|
border-radius: 4px;
|
||||||
|
}
|
||||||
|
</style>
|
||||||
|
</head>
|
||||||
|
<body>
|
||||||
|
<div class="header">
|
||||||
|
<h1>Real-time CAN Signal Graph</h1>
|
||||||
|
</div>
|
||||||
|
<nav class="nav">
|
||||||
|
<a href="/">Dashboard</a>
|
||||||
|
<a href="/graph" class="active">Graph</a>
|
||||||
|
<a href="/files">Files</a>
|
||||||
|
<a href="/can">CAN Transmit</a>
|
||||||
|
<a href="/settings">Settings</a>
|
||||||
|
</nav>
|
||||||
|
<div class="container">
|
||||||
|
<div class="controls">
|
||||||
|
<button class="btn" onclick="togglePause()" id="btnPause">Pause</button>
|
||||||
|
<button class="btn" onclick="clearGraph()">Clear</button>
|
||||||
|
<div class="signal-list" id="signalList"></div>
|
||||||
|
</div>
|
||||||
|
<div class="graph-container">
|
||||||
|
<div id="chart"></div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<script>
|
||||||
|
let ws = null;
|
||||||
|
let uplot = null;
|
||||||
|
let paused = false;
|
||||||
|
let maxPoints = 500;
|
||||||
|
|
||||||
|
const colors = [
|
||||||
|
'#e94560', '#00d9ff', '#f39c12', '#2ecc71',
|
||||||
|
'#9b59b6', '#1abc9c', '#e74c3c', '#3498db',
|
||||||
|
'#f1c40f', '#95a5a6'
|
||||||
|
];
|
||||||
|
|
||||||
|
let signals = [];
|
||||||
|
let data = [[], [], [], [], [], [], [], [], [], [], []];
|
||||||
|
|
||||||
|
function initChart() {
|
||||||
|
const opts = {
|
||||||
|
width: document.getElementById('chart').offsetWidth,
|
||||||
|
height: 500,
|
||||||
|
title: "CAN Signals",
|
||||||
|
axes: [
|
||||||
|
{ label: "Time" },
|
||||||
|
{ label: "Value" }
|
||||||
|
],
|
||||||
|
scales: {
|
||||||
|
x: { time: true },
|
||||||
|
y: { auto: true }
|
||||||
|
},
|
||||||
|
series: [
|
||||||
|
{ label: "Time" }
|
||||||
|
]
|
||||||
|
};
|
||||||
|
|
||||||
|
for (let i = 0; i < 10; i++) {
|
||||||
|
opts.series.push({
|
||||||
|
label: `Signal ${i + 1}`,
|
||||||
|
stroke: colors[i],
|
||||||
|
width: 2
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
uplot = new uPlot(opts, data, document.getElementById('chart'));
|
||||||
|
}
|
||||||
|
|
||||||
|
function connectWebSocket() {
|
||||||
|
const host = window.location.hostname;
|
||||||
|
const wsPort = 81;
|
||||||
|
ws = new WebSocket('ws://' + host + ':' + wsPort);
|
||||||
|
ws.onopen = () => console.log('WebSocket connected');
|
||||||
|
ws.onclose = () => setTimeout(connectWebSocket, 3000);
|
||||||
|
ws.onmessage = (e) => {
|
||||||
|
const msg = JSON.parse(e.data);
|
||||||
|
if (msg.type === 'signal') {
|
||||||
|
msg.signals.forEach((sig, i) => {
|
||||||
|
addPoint(sig.signal_id, sig.value, msg.timestamp);
|
||||||
|
});
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
function updateGraph(msg) {
|
||||||
|
const timestamp = msg.timestamp / 1000;
|
||||||
|
|
||||||
|
// Add time to first series
|
||||||
|
data[0].push(timestamp);
|
||||||
|
|
||||||
|
// Add values for each signal
|
||||||
|
for (let i = 0; i < 10; i++) {
|
||||||
|
const signal = msg.signals[i];
|
||||||
|
if (signal) {
|
||||||
|
data[i + 1].push(signal.value);
|
||||||
|
updateSignalList(i, signal.id, signal.value);
|
||||||
|
} else {
|
||||||
|
data[i + 1].push(null);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Keep only maxPoints
|
||||||
|
if (data[0].length > maxPoints) {
|
||||||
|
for (let i = 0; i < data.length; i++) {
|
||||||
|
data[i].shift();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
uplot.setData(data);
|
||||||
|
}
|
||||||
|
|
||||||
|
function updateSignalList(index, id, value) {
|
||||||
|
const list = document.getElementById('signalList');
|
||||||
|
let item = document.getElementById('signal-' + index);
|
||||||
|
if (!item) {
|
||||||
|
item = document.createElement('div');
|
||||||
|
item.className = 'signal-item';
|
||||||
|
item.id = 'signal-' + index;
|
||||||
|
item.innerHTML = `
|
||||||
|
<div class="signal-color" style="background: ${colors[index]}"></div>
|
||||||
|
<span id="signal-name-${index}">${id}</span>:
|
||||||
|
<span id="signal-val-${index}">${value.toFixed(2)}</span>
|
||||||
|
`;
|
||||||
|
list.appendChild(item);
|
||||||
|
} else {
|
||||||
|
document.getElementById('signal-val-' + index).textContent = value.toFixed(2);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
function togglePause() {
|
||||||
|
paused = !paused;
|
||||||
|
document.getElementById('btnPause').textContent = paused ? 'Resume' : 'Pause';
|
||||||
|
}
|
||||||
|
|
||||||
|
function clearGraph() {
|
||||||
|
data = [[], [], [], [], [], [], [], [], [], [], []];
|
||||||
|
uplot.setData(data);
|
||||||
|
document.getElementById('signalList').innerHTML = '';
|
||||||
|
}
|
||||||
|
|
||||||
|
window.addEventListener('resize', () => {
|
||||||
|
uplot.setSize({
|
||||||
|
width: document.getElementById('chart').offsetWidth,
|
||||||
|
height: 500
|
||||||
|
});
|
||||||
|
});
|
||||||
|
|
||||||
|
initChart();
|
||||||
|
connectWebSocket();
|
||||||
|
</script>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
|
)rawliteral";
|
||||||
|
|
||||||
|
#endif // WEB_GRAPH_H
|
||||||
211
web_index.h
Normal file
211
web_index.h
Normal file
@@ -0,0 +1,211 @@
|
|||||||
|
#ifndef WEB_INDEX_H
|
||||||
|
#define WEB_INDEX_H
|
||||||
|
|
||||||
|
const char HTML_INDEX[] = R"rawliteral(
|
||||||
|
<!DOCTYPE html>
|
||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta charset="UTF-8">
|
||||||
|
<meta name="viewport" content="width=device-width, initial-scale=1.0">
|
||||||
|
<title>ESP32 CAN FD Logger</title>
|
||||||
|
<style>
|
||||||
|
* { margin: 0; padding: 0; box-sizing: border-box; }
|
||||||
|
body {
|
||||||
|
font-family: -apple-system, BlinkMacSystemFont, 'Segoe UI', Roboto, sans-serif;
|
||||||
|
background: #1a1a2e;
|
||||||
|
color: #eee;
|
||||||
|
line-height: 1.6;
|
||||||
|
}
|
||||||
|
.header {
|
||||||
|
background: #16213e;
|
||||||
|
padding: 1rem;
|
||||||
|
text-align: center;
|
||||||
|
border-bottom: 2px solid #e94560;
|
||||||
|
}
|
||||||
|
.header h1 { color: #e94560; font-size: 1.5rem; }
|
||||||
|
.nav {
|
||||||
|
background: #0f3460;
|
||||||
|
padding: 0.5rem;
|
||||||
|
display: flex;
|
||||||
|
justify-content: center;
|
||||||
|
flex-wrap: wrap;
|
||||||
|
gap: 0.5rem;
|
||||||
|
}
|
||||||
|
.nav a {
|
||||||
|
color: #fff;
|
||||||
|
text-decoration: none;
|
||||||
|
padding: 0.5rem 1rem;
|
||||||
|
border-radius: 4px;
|
||||||
|
transition: background 0.3s;
|
||||||
|
}
|
||||||
|
.nav a:hover, .nav a.active { background: #e94560; }
|
||||||
|
.container {
|
||||||
|
max-width: 1200px;
|
||||||
|
margin: 0 auto;
|
||||||
|
padding: 2rem;
|
||||||
|
}
|
||||||
|
.status-grid {
|
||||||
|
display: grid;
|
||||||
|
grid-template-columns: repeat(auto-fit, minmax(250px, 1fr));
|
||||||
|
gap: 1rem;
|
||||||
|
margin-bottom: 2rem;
|
||||||
|
}
|
||||||
|
.status-card {
|
||||||
|
background: #16213e;
|
||||||
|
padding: 1.5rem;
|
||||||
|
border-radius: 8px;
|
||||||
|
border-left: 4px solid #e94560;
|
||||||
|
}
|
||||||
|
.status-card h3 { color: #e94560; margin-bottom: 0.5rem; }
|
||||||
|
.status-value { font-size: 2rem; font-weight: bold; }
|
||||||
|
.btn {
|
||||||
|
background: #e94560;
|
||||||
|
color: #fff;
|
||||||
|
border: none;
|
||||||
|
padding: 1rem 2rem;
|
||||||
|
font-size: 1rem;
|
||||||
|
border-radius: 4px;
|
||||||
|
cursor: pointer;
|
||||||
|
transition: background 0.3s;
|
||||||
|
margin: 0.5rem;
|
||||||
|
}
|
||||||
|
.btn:hover { background: #ff6b6b; }
|
||||||
|
.btn:disabled { background: #666; cursor: not-allowed; }
|
||||||
|
.btn-green { background: #00d9ff; }
|
||||||
|
.btn-green:hover { background: #00b8d4; }
|
||||||
|
.controls {
|
||||||
|
text-align: center;
|
||||||
|
margin: 2rem 0;
|
||||||
|
}
|
||||||
|
.log {
|
||||||
|
background: #16213e;
|
||||||
|
padding: 1rem;
|
||||||
|
border-radius: 8px;
|
||||||
|
height: 200px;
|
||||||
|
overflow-y: auto;
|
||||||
|
font-family: monospace;
|
||||||
|
font-size: 0.875rem;
|
||||||
|
}
|
||||||
|
.log-entry { margin-bottom: 0.25rem; }
|
||||||
|
.log-entry.error { color: #ff6b6b; }
|
||||||
|
.log-entry.success { color: #00d9ff; }
|
||||||
|
</style>
|
||||||
|
</head>
|
||||||
|
<body>
|
||||||
|
<div class="header">
|
||||||
|
<h1>ESP32 CAN FD Logger</h1>
|
||||||
|
</div>
|
||||||
|
<nav class="nav">
|
||||||
|
<a href="/" class="active">Dashboard</a>
|
||||||
|
<a href="/graph">Graph</a>
|
||||||
|
<a href="/files">Files</a>
|
||||||
|
<a href="/can">CAN Transmit</a>
|
||||||
|
<a href="/settings">Settings</a>
|
||||||
|
<a href="/test">Test</a>
|
||||||
|
</nav>
|
||||||
|
<div class="container">
|
||||||
|
<div class="status-grid">
|
||||||
|
<div class="status-card">
|
||||||
|
<h3>WiFi Status</h3>
|
||||||
|
<div class="status-value" id="wifiStatus">AP Mode</div>
|
||||||
|
<div id="wifiIP">192.168.4.1</div>
|
||||||
|
</div>
|
||||||
|
<div class="status-card">
|
||||||
|
<h3>CAN Status</h3>
|
||||||
|
<div class="status-value" id="canStatus">Active</div>
|
||||||
|
<div id="canStats">RX: 0 | TX: 0</div>
|
||||||
|
</div>
|
||||||
|
<div class="status-card">
|
||||||
|
<h3>SD Card</h3>
|
||||||
|
<div class="status-value" id="sdStatus">OK</div>
|
||||||
|
<div id="sdSpace">-- MB free</div>
|
||||||
|
</div>
|
||||||
|
<div class="status-card">
|
||||||
|
<h3>Logging</h3>
|
||||||
|
<div class="status-value" id="logStatus">Stopped</div>
|
||||||
|
<div id="logFile">--</div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<div class="controls">
|
||||||
|
<button class="btn btn-green" id="btnStart" onclick="startLogging()">Start Logging</button>
|
||||||
|
<button class="btn" id="btnStop" onclick="stopLogging()" disabled>Stop Logging</button>
|
||||||
|
</div>
|
||||||
|
<div class="log" id="log"></div>
|
||||||
|
</div>
|
||||||
|
<script>
|
||||||
|
let ws = null;
|
||||||
|
let logging = false;
|
||||||
|
|
||||||
|
function log(msg, type='info') {
|
||||||
|
const logDiv = document.getElementById('log');
|
||||||
|
const entry = document.createElement('div');
|
||||||
|
entry.className = 'log-entry ' + type;
|
||||||
|
entry.textContent = new Date().toLocaleTimeString() + ' - ' + msg;
|
||||||
|
logDiv.appendChild(entry);
|
||||||
|
logDiv.scrollTop = logDiv.scrollHeight;
|
||||||
|
}
|
||||||
|
|
||||||
|
function connectWebSocket() {
|
||||||
|
const host = window.location.hostname;
|
||||||
|
const wsPort = 81;
|
||||||
|
ws = new WebSocket('ws://' + host + ':' + wsPort);
|
||||||
|
ws.onopen = () => log('WebSocket connected', 'success');
|
||||||
|
ws.onclose = () => {
|
||||||
|
log('WebSocket disconnected, reconnecting...', 'error');
|
||||||
|
setTimeout(connectWebSocket, 3000);
|
||||||
|
};
|
||||||
|
ws.onerror = (e) => log('WebSocket error', 'error');
|
||||||
|
ws.onmessage = (e) => {
|
||||||
|
const data = JSON.parse(e.data);
|
||||||
|
if (data.type === 'status') updateStatus(data);
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
function updateStatus(data) {
|
||||||
|
document.getElementById('canStats').textContent =
|
||||||
|
`RX: ${data.rx} | TX: ${data.tx}`;
|
||||||
|
}
|
||||||
|
|
||||||
|
function startLogging() {
|
||||||
|
fetch('/api/logging/start', {method: 'POST'})
|
||||||
|
.then(r => r.json())
|
||||||
|
.then(data => {
|
||||||
|
logging = true;
|
||||||
|
document.getElementById('btnStart').disabled = true;
|
||||||
|
document.getElementById('btnStop').disabled = false;
|
||||||
|
document.getElementById('logStatus').textContent = 'Running';
|
||||||
|
log('Logging started', 'success');
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
function stopLogging() {
|
||||||
|
fetch('/api/logging/stop', {method: 'POST'})
|
||||||
|
.then(r => r.json())
|
||||||
|
.then(data => {
|
||||||
|
logging = false;
|
||||||
|
document.getElementById('btnStart').disabled = false;
|
||||||
|
document.getElementById('btnStop').disabled = true;
|
||||||
|
document.getElementById('logStatus').textContent = 'Stopped';
|
||||||
|
log('Logging stopped');
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
function loadStatus() {
|
||||||
|
fetch('/api/status')
|
||||||
|
.then(r => r.json())
|
||||||
|
.then(data => {
|
||||||
|
document.getElementById('wifiStatus').textContent =
|
||||||
|
data.ap ? 'AP Mode' : (data.sta ? 'STA Mode' : 'Off');
|
||||||
|
document.getElementById('wifiIP').textContent = data.ip;
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
connectWebSocket();
|
||||||
|
loadStatus();
|
||||||
|
log('Dashboard loaded');
|
||||||
|
</script>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
|
)rawliteral";
|
||||||
|
|
||||||
|
#endif // WEB_INDEX_H
|
||||||
687
web_server.cpp
Normal file
687
web_server.cpp
Normal file
@@ -0,0 +1,687 @@
|
|||||||
|
// web_server.cpp - Web Server Implementation with WebServer and WebSocketsServer
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include <WiFi.h>
|
||||||
|
#include <WebServer.h>
|
||||||
|
#include <WebSocketsServer.h>
|
||||||
|
#include <ESPmDNS.h>
|
||||||
|
#include <SD_MMC.h>
|
||||||
|
#include <ArduinoJson.h>
|
||||||
|
|
||||||
|
#include "web_server.h"
|
||||||
|
#include "task_config.h"
|
||||||
|
#include "can_handler.h"
|
||||||
|
#include "sd_logger.h"
|
||||||
|
#include "rtc_manager.h"
|
||||||
|
#include "signal_manager.h"
|
||||||
|
#include "dbc_parser.h"
|
||||||
|
#include "auto_trigger.h"
|
||||||
|
#include "psram_buffer.h"
|
||||||
|
#include "test_handler.h"
|
||||||
|
|
||||||
|
#include "data/web_index.h"
|
||||||
|
#include "data/web_settings.h"
|
||||||
|
#include "data/web_files.h"
|
||||||
|
#include "data/web_can.h"
|
||||||
|
#include "data/web_graph.h"
|
||||||
|
#include "data/web_test.h"
|
||||||
|
|
||||||
|
WebServer server(WEB_SERVER_PORT);
|
||||||
|
WebSocketsServer webSocket(81);
|
||||||
|
|
||||||
|
bool wifiInitialized = false;
|
||||||
|
bool apModeActive = false;
|
||||||
|
bool staModeActive = false;
|
||||||
|
|
||||||
|
WiFiConfig wifiConfig;
|
||||||
|
|
||||||
|
static char wsBuffer[2048];
|
||||||
|
|
||||||
|
bool initWiFi() {
|
||||||
|
Serial.println("Initializing WiFi...");
|
||||||
|
|
||||||
|
loadWiFiConfig();
|
||||||
|
|
||||||
|
if (!startAPMode()) {
|
||||||
|
Serial.println("Failed to start AP mode!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (wifiConfig.useSTA && strlen(wifiConfig.staSSID) > 0) {
|
||||||
|
startSTAMode(wifiConfig.staSSID, wifiConfig.staPassword);
|
||||||
|
}
|
||||||
|
|
||||||
|
wifiInitialized = true;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool startAPMode() {
|
||||||
|
Serial.println("Starting WiFi AP mode...");
|
||||||
|
|
||||||
|
WiFi.mode(WIFI_AP_STA);
|
||||||
|
|
||||||
|
bool result = WiFi.softAP(WIFI_AP_SSID, WIFI_AP_PASSWORD, WIFI_AP_CHANNEL, 0, WIFI_AP_MAX_CLIENTS);
|
||||||
|
|
||||||
|
if (result) {
|
||||||
|
apModeActive = true;
|
||||||
|
Serial.printf("AP Started: %s\n", WIFI_AP_SSID);
|
||||||
|
Serial.printf("AP IP: %s\n", WiFi.softAPIP().toString().c_str());
|
||||||
|
initMDNS();
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool startSTAMode(const char* ssid, const char* password) {
|
||||||
|
Serial.printf("Connecting to WiFi: %s\n", ssid);
|
||||||
|
|
||||||
|
WiFi.begin(ssid, password);
|
||||||
|
|
||||||
|
int attempts = 0;
|
||||||
|
while (WiFi.status() != WL_CONNECTED && attempts < 20) {
|
||||||
|
delay(500);
|
||||||
|
Serial.print(".");
|
||||||
|
attempts++;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (WiFi.status() == WL_CONNECTED) {
|
||||||
|
staModeActive = true;
|
||||||
|
Serial.println("\nWiFi Connected!");
|
||||||
|
Serial.printf("STA IP: %s\n", WiFi.localIP().toString().c_str());
|
||||||
|
return true;
|
||||||
|
} else {
|
||||||
|
Serial.println("\nWiFi connection failed!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void stopWiFi() {
|
||||||
|
WiFi.disconnect(true);
|
||||||
|
WiFi.mode(WIFI_OFF);
|
||||||
|
apModeActive = false;
|
||||||
|
staModeActive = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool initMDNS() {
|
||||||
|
if (!MDNS.begin("esp32-can")) {
|
||||||
|
Serial.println("mDNS failed to start!");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
MDNS.addService("http", "tcp", WEB_SERVER_PORT);
|
||||||
|
MDNS.addService("ws", "tcp", 81);
|
||||||
|
Serial.println("mDNS started: esp32-can.local");
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void webSocketEvent(uint8_t num, WStype_t type, uint8_t * payload, size_t length) {
|
||||||
|
switch(type) {
|
||||||
|
case WStype_DISCONNECTED:
|
||||||
|
Serial.printf("[%u] Disconnected!\n", num);
|
||||||
|
break;
|
||||||
|
case WStype_CONNECTED:
|
||||||
|
Serial.printf("[%u] Connected from %s\n", num, webSocket.remoteIP(num).toString().c_str());
|
||||||
|
break;
|
||||||
|
case WStype_TEXT:
|
||||||
|
Serial.printf("[%u] Message: %s\n", num, payload);
|
||||||
|
break;
|
||||||
|
case WStype_BIN:
|
||||||
|
case WStype_ERROR:
|
||||||
|
case WStype_FRAGMENT_TEXT_START:
|
||||||
|
case WStype_FRAGMENT_BIN_START:
|
||||||
|
case WStype_FRAGMENT:
|
||||||
|
case WStype_FRAGMENT_FIN:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void broadcastToClients(const char* message) {
|
||||||
|
webSocket.broadcastTXT(message);
|
||||||
|
}
|
||||||
|
|
||||||
|
void broadcastSignalData(const GraphSignal* signals, uint8_t count) {
|
||||||
|
StaticJsonDocument<2048> doc;
|
||||||
|
doc["type"] = "signal";
|
||||||
|
doc["timestamp"] = millis();
|
||||||
|
|
||||||
|
JsonArray sigArray = doc.createNestedArray("signals");
|
||||||
|
for (uint8_t i = 0; i < count; i++) {
|
||||||
|
JsonObject sig = sigArray.createNestedObject();
|
||||||
|
sig["id"] = signals[i].signal_id;
|
||||||
|
sig["value"] = signals[i].value;
|
||||||
|
}
|
||||||
|
|
||||||
|
serializeJson(doc, wsBuffer, sizeof(wsBuffer));
|
||||||
|
webSocket.broadcastTXT(wsBuffer);
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleRoot() {
|
||||||
|
server.send(200, "text/html", HTML_INDEX);
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleSettings() {
|
||||||
|
server.send(200, "text/html", HTML_SETTINGS);
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleFiles() {
|
||||||
|
server.send(200, "text/html", HTML_FILES);
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleCAN() {
|
||||||
|
server.send(200, "text/html", HTML_CAN);
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleGraph() {
|
||||||
|
server.send(200, "text/html", HTML_GRAPH);
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleTest() {
|
||||||
|
server.send(200, "text/html", HTML_TEST);
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPIStatus() {
|
||||||
|
StaticJsonDocument<1024> doc;
|
||||||
|
|
||||||
|
doc["wifi"] = wifiInitialized;
|
||||||
|
doc["ap"] = apModeActive;
|
||||||
|
doc["sta"] = staModeActive;
|
||||||
|
doc["ap_ip"] = WiFi.softAPIP().toString();
|
||||||
|
|
||||||
|
if (staModeActive) {
|
||||||
|
doc["sta_ip"] = WiFi.localIP().toString();
|
||||||
|
}
|
||||||
|
|
||||||
|
doc["can"]["initialized"] = canInitialized;
|
||||||
|
uint32_t rx, tx, err;
|
||||||
|
getCANStats(rx, tx, err);
|
||||||
|
doc["can"]["rx_count"] = rx;
|
||||||
|
doc["can"]["tx_count"] = tx;
|
||||||
|
doc["can"]["error_count"] = err;
|
||||||
|
doc["can"]["mode"] = getCANMode();
|
||||||
|
doc["can"]["buffer_used"] = canFrameBuffer.available();
|
||||||
|
doc["can"]["buffer_capacity"] = canFrameBuffer.capacity();
|
||||||
|
|
||||||
|
doc["sd"]["initialized"] = sdInitialized;
|
||||||
|
doc["sd"]["total_mb"] = getSDCardSize() / (1024 * 1024);
|
||||||
|
doc["sd"]["free_mb"] = getFreeSpace() / (1024 * 1024);
|
||||||
|
|
||||||
|
doc["rtc"]["initialized"] = rtcInitialized;
|
||||||
|
|
||||||
|
doc["log"]["filename"] = getCurrentLogFilename();
|
||||||
|
|
||||||
|
doc["memory"]["heap_free"] = ESP.getFreeHeap();
|
||||||
|
doc["memory"]["heap_total"] = ESP.getHeapSize();
|
||||||
|
if (psramFound()) {
|
||||||
|
doc["memory"]["psram_free"] = ESP.getFreePsram();
|
||||||
|
doc["memory"]["psram_total"] = ESP.getPsramSize();
|
||||||
|
doc["memory"]["psram_used_mb"] = (ESP.getPsramSize() - ESP.getFreePsram()) / (1024 * 1024);
|
||||||
|
}
|
||||||
|
|
||||||
|
String output;
|
||||||
|
serializeJson(doc, output);
|
||||||
|
server.send(200, "application/json", output);
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPIMemory() {
|
||||||
|
StaticJsonDocument<512> doc;
|
||||||
|
|
||||||
|
doc["heap"]["free"] = ESP.getFreeHeap();
|
||||||
|
doc["heap"]["total"] = ESP.getHeapSize();
|
||||||
|
doc["heap"]["used"] = ESP.getHeapSize() - ESP.getFreeHeap();
|
||||||
|
|
||||||
|
if (psramFound()) {
|
||||||
|
doc["psram"]["found"] = true;
|
||||||
|
doc["psram"]["free"] = ESP.getFreePsram();
|
||||||
|
doc["psram"]["total"] = ESP.getPsramSize();
|
||||||
|
doc["psram"]["used"] = ESP.getPsramSize() - ESP.getFreePsram();
|
||||||
|
doc["psram"]["free_mb"] = ESP.getFreePsram() / (1024 * 1024);
|
||||||
|
doc["psram"]["total_mb"] = ESP.getPsramSize() / (1024 * 1024);
|
||||||
|
} else {
|
||||||
|
doc["psram"]["found"] = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
doc["can_buffer"]["used"] = canFrameBuffer.available();
|
||||||
|
doc["can_buffer"]["capacity"] = canFrameBuffer.capacity();
|
||||||
|
doc["can_buffer"]["free"] = canFrameBuffer.freeSpace();
|
||||||
|
|
||||||
|
String output;
|
||||||
|
serializeJson(doc, output);
|
||||||
|
server.send(200, "application/json", output);
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPIFileList() {
|
||||||
|
StaticJsonDocument<4096> doc;
|
||||||
|
JsonArray files = doc.to<JsonArray>();
|
||||||
|
|
||||||
|
if (sdInitialized) {
|
||||||
|
File root = SD_MMC.open(LOGS_DIR);
|
||||||
|
if (root && root.isDirectory()) {
|
||||||
|
File file = root.openNextFile();
|
||||||
|
while (file) {
|
||||||
|
if (!file.isDirectory() && String(file.name()).endsWith(".pcap")) {
|
||||||
|
JsonObject f = files.createNestedObject();
|
||||||
|
f["name"] = file.name();
|
||||||
|
f["size"] = file.size();
|
||||||
|
f["time"] = file.getLastWrite();
|
||||||
|
}
|
||||||
|
file = root.openNextFile();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
String output;
|
||||||
|
serializeJson(doc, output);
|
||||||
|
server.send(200, "application/json", output);
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPIFileDownload() {
|
||||||
|
if (!server.hasArg("name")) {
|
||||||
|
server.send(400, "application/json", "{\"error\":\"Missing name parameter\"}");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
String filename = server.arg("name");
|
||||||
|
String path = String(LOGS_DIR) + "/" + filename;
|
||||||
|
|
||||||
|
if (!SD_MMC.exists(path)) {
|
||||||
|
server.send(404, "application/json", "{\"error\":\"File not found\"}");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
File file = SD_MMC.open(path, "r");
|
||||||
|
if (!file) {
|
||||||
|
server.send(500, "application/json", "{\"error\":\"Cannot open file\"}");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
server.streamFile(file, "application/octet-stream");
|
||||||
|
file.close();
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPIFileDelete() {
|
||||||
|
if (!server.hasArg("name")) {
|
||||||
|
server.send(400, "application/json", "{\"error\":\"Missing name parameter\"}");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
String filename = server.arg("name");
|
||||||
|
|
||||||
|
if (deleteLogFile(filename.c_str())) {
|
||||||
|
server.send(200, "application/json", "{\"status\":\"deleted\"}");
|
||||||
|
} else {
|
||||||
|
server.send(500, "application/json", "{\"error\":\"Delete failed\"}");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPICANSend() {
|
||||||
|
if (!server.hasArg("plain")) {
|
||||||
|
server.send(400, "application/json", "{\"error\":\"Missing body\"}");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
String body = server.arg("plain");
|
||||||
|
StaticJsonDocument<512> doc;
|
||||||
|
DeserializationError error = deserializeJson(doc, body);
|
||||||
|
|
||||||
|
if (error) {
|
||||||
|
server.send(400, "application/json", "{\"error\":\"Invalid JSON\"}");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
String idStr = doc["id"] | "0x100";
|
||||||
|
uint32_t id = 0;
|
||||||
|
if (idStr.startsWith("0x") || idStr.startsWith("0X")) {
|
||||||
|
id = strtol(idStr.c_str(), NULL, 16);
|
||||||
|
} else {
|
||||||
|
id = idStr.toInt();
|
||||||
|
}
|
||||||
|
|
||||||
|
String frameType = doc["type"] | "standard";
|
||||||
|
bool ext = (frameType == "extended");
|
||||||
|
bool fd = (frameType == "fd") || (doc["isFD"] | false);
|
||||||
|
|
||||||
|
JsonArray dataArr = doc["data"];
|
||||||
|
uint8_t data[64] = {0};
|
||||||
|
uint8_t len = doc["length"] | 8;
|
||||||
|
|
||||||
|
int i = 0;
|
||||||
|
for (JsonVariant v : dataArr) {
|
||||||
|
if (i < 64) {
|
||||||
|
data[i++] = v.as<uint8_t>();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ext) id |= 0x80000000;
|
||||||
|
|
||||||
|
if (sendCANFrame(id, data, len, fd)) {
|
||||||
|
server.send(200, "application/json", "{\"status\":\"sent\"}");
|
||||||
|
} else {
|
||||||
|
server.send(500, "application/json", "{\"error\":\"Send failed\"}");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPIWiFiConfig() {
|
||||||
|
if (!server.hasArg("plain")) {
|
||||||
|
server.send(400, "application/json", "{\"error\":\"Missing body\"}");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
String body = server.arg("plain");
|
||||||
|
StaticJsonDocument<256> doc;
|
||||||
|
DeserializationError error = deserializeJson(doc, body);
|
||||||
|
|
||||||
|
if (error) {
|
||||||
|
server.send(400, "application/json", "{\"error\":\"Invalid JSON\"}");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (doc.containsKey("ssid") && doc.containsKey("password")) {
|
||||||
|
strlcpy(wifiConfig.staSSID, doc["ssid"], sizeof(wifiConfig.staSSID));
|
||||||
|
strlcpy(wifiConfig.staPassword, doc["password"], sizeof(wifiConfig.staPassword));
|
||||||
|
wifiConfig.useSTA = true;
|
||||||
|
saveWiFiConfig();
|
||||||
|
|
||||||
|
server.send(200, "application/json", "{\"status\":\"saved\",\"reconnect\":true}");
|
||||||
|
} else {
|
||||||
|
server.send(400, "application/json", "{\"error\":\"Missing ssid or password\"}");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPILoggingStart() {
|
||||||
|
if (startLogFile()) {
|
||||||
|
server.send(200, "application/json", "{\"status\":\"started\"}");
|
||||||
|
} else {
|
||||||
|
server.send(500, "application/json", "{\"error\":\"Start failed\"}");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPILoggingStop() {
|
||||||
|
closeLogFile();
|
||||||
|
server.send(200, "application/json", "{\"status\":\"stopped\"}");
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPIDBCUpload() {
|
||||||
|
if (!server.hasArg("plain")) {
|
||||||
|
server.send(400, "application/json", "{\"error\":\"Missing body\"}");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
String content = server.arg("plain");
|
||||||
|
|
||||||
|
if (parseDBC(content.c_str())) {
|
||||||
|
server.send(200, "application/json", "{\"status\":\"loaded\"}");
|
||||||
|
} else {
|
||||||
|
server.send(400, "application/json", "{\"error\":\"Parse failed\"}");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPITimeSync() {
|
||||||
|
if (!server.hasArg("plain")) {
|
||||||
|
server.send(400, "application/json", "{\"error\":\"Missing body\"}");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
String body = server.arg("plain");
|
||||||
|
StaticJsonDocument<128> doc;
|
||||||
|
DeserializationError error = deserializeJson(doc, body);
|
||||||
|
|
||||||
|
if (error) {
|
||||||
|
server.send(400, "application/json", "{\"error\":\"Invalid JSON\"}");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (doc.containsKey("timestamp")) {
|
||||||
|
uint32_t timestamp = doc["timestamp"];
|
||||||
|
setRTCTime(timestamp);
|
||||||
|
server.send(200, "application/json", "{\"status\":\"synced\"}");
|
||||||
|
} else {
|
||||||
|
server.send(400, "application/json", "{\"error\":\"Missing timestamp\"}");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPIRestart() {
|
||||||
|
server.send(200, "application/json", "{\"status\":\"restarting\"}");
|
||||||
|
delay(100);
|
||||||
|
ESP.restart();
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPICANConfig() {
|
||||||
|
if (!server.hasArg("plain")) {
|
||||||
|
server.send(400, "application/json", "{\"error\":\"Missing body\"}");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
String body = server.arg("plain");
|
||||||
|
StaticJsonDocument<256> doc;
|
||||||
|
DeserializationError error = deserializeJson(doc, body);
|
||||||
|
|
||||||
|
if (error) {
|
||||||
|
server.send(400, "application/json", "{\"error\":\"Invalid JSON\"}");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t arbBaud = doc["arbBaud"] | CAN_DEFAULT_ARBITRATION_BAUDRATE;
|
||||||
|
uint32_t dataBaud = doc["dataBaud"] | CAN_DEFAULT_DATA_BAUDRATE;
|
||||||
|
uint8_t mode = doc["mode"] | 0;
|
||||||
|
bool enableFD = doc["enableFD"] | true;
|
||||||
|
|
||||||
|
if (setCANBaudrateAndMode(arbBaud, dataBaud, mode, enableFD)) {
|
||||||
|
server.send(200, "application/json", "{\"status\":\"configured\"}");
|
||||||
|
} else {
|
||||||
|
server.send(500, "application/json", "{\"error\":\"Configuration failed\"}");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPITriggerConfig() {
|
||||||
|
if (!server.hasArg("plain")) {
|
||||||
|
server.send(200, "application/json", "{\"error\":\"Missing body\"}");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
String body = server.arg("plain");
|
||||||
|
StaticJsonDocument<512> doc;
|
||||||
|
deserializeJson(doc, body);
|
||||||
|
|
||||||
|
if (doc.containsKey("enabled")) {
|
||||||
|
enableTrigger(doc["enabled"]);
|
||||||
|
}
|
||||||
|
if (doc.containsKey("logic")) {
|
||||||
|
setLogicalOperator(doc["logic"] == "AND" ? LOGIC_AND : LOGIC_OR);
|
||||||
|
}
|
||||||
|
|
||||||
|
char buffer[256];
|
||||||
|
getTriggerStatusJSON(buffer, sizeof(buffer));
|
||||||
|
server.send(200, "application/json", buffer);
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPISignalAdd() {
|
||||||
|
if (!server.hasArg("plain")) {
|
||||||
|
server.send(400, "application/json", "{\"error\":\"Missing body\"}");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
String body = server.arg("plain");
|
||||||
|
StaticJsonDocument<256> doc;
|
||||||
|
deserializeJson(doc, body);
|
||||||
|
|
||||||
|
const char* name = doc["name"];
|
||||||
|
uint32_t canId = doc["canId"];
|
||||||
|
uint32_t startBit = doc["startBit"];
|
||||||
|
uint32_t length = doc["length"];
|
||||||
|
bool littleEndian = doc["littleEndian"] | true;
|
||||||
|
bool isSigned = doc["signed"] | false;
|
||||||
|
float factor = doc["factor"] | 1.0;
|
||||||
|
float offset = doc["offset"] | 0.0;
|
||||||
|
|
||||||
|
if (addManualSignal(name, canId, startBit, length, littleEndian, isSigned, factor, offset)) {
|
||||||
|
server.send(200, "application/json", "{\"status\":\"added\"}");
|
||||||
|
} else {
|
||||||
|
server.send(500, "application/json", "{\"error\":\"Failed to add signal\"}");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPISignalList() {
|
||||||
|
char buffer[2048];
|
||||||
|
getSignalsJSON(buffer, sizeof(buffer));
|
||||||
|
server.send(200, "application/json", buffer);
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPITestStart() {
|
||||||
|
if (isTestRunning()) {
|
||||||
|
server.send(400, "application/json", "{\"error\":\"Test already running\"}");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!server.hasArg("plain")) {
|
||||||
|
server.send(400, "application/json", "{\"error\":\"Missing body\"}");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
String body = server.arg("plain");
|
||||||
|
StaticJsonDocument<256> doc;
|
||||||
|
deserializeJson(doc, body);
|
||||||
|
|
||||||
|
String testType = doc["type"] | "loopback";
|
||||||
|
uint32_t frameCount = doc["frames"] | 1000;
|
||||||
|
uint32_t interval = doc["interval"] | 1000;
|
||||||
|
uint8_t dataLen = doc["dataLen"] | 64;
|
||||||
|
bool useFD = doc["useFD"] | true;
|
||||||
|
uint32_t canId = doc["canId"] | 0x100;
|
||||||
|
|
||||||
|
bool started = false;
|
||||||
|
|
||||||
|
if (testType == "loopback") {
|
||||||
|
started = startLoopbackTest(frameCount, interval);
|
||||||
|
} else if (testType == "stress") {
|
||||||
|
started = startStressTest(frameCount, dataLen, useFD);
|
||||||
|
} else if (testType == "sequence") {
|
||||||
|
started = startSequenceTest(frameCount, canId);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (started) {
|
||||||
|
server.send(200, "application/json", "{\"status\":\"started\"}");
|
||||||
|
} else {
|
||||||
|
server.send(500, "application/json", "{\"error\":\"Failed to start test\"}");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPITestStop() {
|
||||||
|
stopTest();
|
||||||
|
server.send(200, "application/json", "{\"status\":\"stopped\"}");
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleAPITestStatus() {
|
||||||
|
char buffer[512];
|
||||||
|
getTestResultJSON(buffer, sizeof(buffer));
|
||||||
|
server.send(200, "application/json", buffer);
|
||||||
|
}
|
||||||
|
|
||||||
|
void handleNotFound() {
|
||||||
|
server.send(404, "text/plain", "Not Found");
|
||||||
|
}
|
||||||
|
|
||||||
|
bool initWebServer() {
|
||||||
|
Serial.println("Initializing Web Server...");
|
||||||
|
|
||||||
|
server.on("/", handleRoot);
|
||||||
|
server.on("/settings", handleSettings);
|
||||||
|
server.on("/files", handleFiles);
|
||||||
|
server.on("/can", handleCAN);
|
||||||
|
server.on("/graph", handleGraph);
|
||||||
|
server.on("/test", handleTest);
|
||||||
|
|
||||||
|
server.on("/api/status", handleAPIStatus);
|
||||||
|
server.on("/api/memory", handleAPIMemory);
|
||||||
|
server.on("/api/files", handleAPIFileList);
|
||||||
|
server.on("/api/files/download", handleAPIFileDownload);
|
||||||
|
server.on("/api/files/delete", handleAPIFileDelete);
|
||||||
|
server.on("/api/can/send", HTTP_POST, handleAPICANSend);
|
||||||
|
server.on("/api/wifi", HTTP_POST, handleAPIWiFiConfig);
|
||||||
|
server.on("/api/logging/start", handleAPILoggingStart);
|
||||||
|
server.on("/api/logging/stop", handleAPILoggingStop);
|
||||||
|
server.on("/api/dbc/upload", HTTP_POST, handleAPIDBCUpload);
|
||||||
|
|
||||||
|
server.on("/api/time", HTTP_POST, handleAPITimeSync);
|
||||||
|
server.on("/api/restart", HTTP_POST, handleAPIRestart);
|
||||||
|
server.on("/api/can/config", HTTP_POST, handleAPICANConfig);
|
||||||
|
server.on("/api/trigger", handleAPITriggerConfig);
|
||||||
|
server.on("/api/signal/add", HTTP_POST, handleAPISignalAdd);
|
||||||
|
server.on("/api/signal/list", handleAPISignalList);
|
||||||
|
|
||||||
|
server.on("/api/test/start", HTTP_POST, handleAPITestStart);
|
||||||
|
server.on("/api/test/stop", handleAPITestStop);
|
||||||
|
server.on("/api/test/status", handleAPITestStatus);
|
||||||
|
|
||||||
|
server.onNotFound(handleNotFound);
|
||||||
|
|
||||||
|
server.begin();
|
||||||
|
|
||||||
|
webSocket.begin();
|
||||||
|
webSocket.onEvent(webSocketEvent);
|
||||||
|
|
||||||
|
Serial.println("Web Server started on port 80");
|
||||||
|
Serial.println("WebSocket started on port 81");
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void webServerTask(void *pvParameters) {
|
||||||
|
Serial.println("Web Server Task started on Core 1");
|
||||||
|
|
||||||
|
if (!initWiFi()) {
|
||||||
|
Serial.println("WiFi initialization failed!");
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!initWebServer()) {
|
||||||
|
Serial.println("Web Server initialization failed!");
|
||||||
|
}
|
||||||
|
|
||||||
|
while (1) {
|
||||||
|
server.handleClient();
|
||||||
|
webSocket.loop();
|
||||||
|
vTaskDelay(pdMS_TO_TICKS(10));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void wsTxTask(void *pvParameters) {
|
||||||
|
Serial.println("WebSocket TX Task started on Core 1");
|
||||||
|
|
||||||
|
CanFrame frame;
|
||||||
|
SignalValue signals[10];
|
||||||
|
uint16_t signalCount = 0;
|
||||||
|
uint32_t lastUpdate = 0;
|
||||||
|
|
||||||
|
while (1) {
|
||||||
|
if (xQueueReceive(graphQueue, &frame, pdMS_TO_TICKS(50)) == pdTRUE) {
|
||||||
|
updateAllSignals(&frame);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t now = millis();
|
||||||
|
if (now - lastUpdate >= 100) {
|
||||||
|
signalCount = getEnabledSignals(signals, 10);
|
||||||
|
if (signalCount > 0) {
|
||||||
|
GraphSignal graphSignals[10];
|
||||||
|
for (uint16_t i = 0; i < signalCount; i++) {
|
||||||
|
strncpy(graphSignals[i].signal_id, signals[i].name, 32);
|
||||||
|
graphSignals[i].value = signals[i].value;
|
||||||
|
graphSignals[i].timestamp = signals[i].timestamp;
|
||||||
|
}
|
||||||
|
broadcastSignalData(graphSignals, signalCount);
|
||||||
|
}
|
||||||
|
lastUpdate = now;
|
||||||
|
}
|
||||||
|
|
||||||
|
updateTrigger();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bool loadWiFiConfig() {
|
||||||
|
wifiConfig.useSTA = false;
|
||||||
|
wifiConfig.staSSID[0] = '\0';
|
||||||
|
wifiConfig.staPassword[0] = '\0';
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool saveWiFiConfig() {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
83
web_server.h
Normal file
83
web_server.h
Normal file
@@ -0,0 +1,83 @@
|
|||||||
|
// web_server.h - Web Server with WebServer and WebSocketsServer
|
||||||
|
|
||||||
|
#ifndef WEB_SERVER_H
|
||||||
|
#define WEB_SERVER_H
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include <WiFi.h>
|
||||||
|
#include <WebServer.h>
|
||||||
|
#include <WebSocketsServer.h>
|
||||||
|
#include <ESPmDNS.h>
|
||||||
|
|
||||||
|
#include "config.h"
|
||||||
|
#include "types.h"
|
||||||
|
|
||||||
|
extern WebServer server;
|
||||||
|
extern WebSocketsServer webSocket;
|
||||||
|
|
||||||
|
extern bool wifiInitialized;
|
||||||
|
extern bool apModeActive;
|
||||||
|
extern bool staModeActive;
|
||||||
|
|
||||||
|
bool initWiFi();
|
||||||
|
bool initWebServer();
|
||||||
|
|
||||||
|
bool startAPMode();
|
||||||
|
bool startSTAMode(const char* ssid, const char* password);
|
||||||
|
void stopWiFi();
|
||||||
|
|
||||||
|
bool initMDNS();
|
||||||
|
|
||||||
|
void webServerTask(void *pvParameters);
|
||||||
|
void wsTxTask(void *pvParameters);
|
||||||
|
|
||||||
|
void webSocketEvent(uint8_t num, WStype_t type, uint8_t * payload, size_t length);
|
||||||
|
|
||||||
|
void broadcastToClients(const char* message);
|
||||||
|
void broadcastSignalData(const GraphSignal* signals, uint8_t count);
|
||||||
|
|
||||||
|
void handleRoot();
|
||||||
|
void handleSettings();
|
||||||
|
void handleFiles();
|
||||||
|
void handleCAN();
|
||||||
|
void handleGraph();
|
||||||
|
void handleTest();
|
||||||
|
|
||||||
|
void handleAPIStatus();
|
||||||
|
void handleAPIMemory();
|
||||||
|
void handleAPIFileList();
|
||||||
|
void handleAPIFileDownload();
|
||||||
|
void handleAPIFileDelete();
|
||||||
|
void handleAPICANSend();
|
||||||
|
void handleAPIWiFiConfig();
|
||||||
|
void handleAPILoggingStart();
|
||||||
|
void handleAPILoggingStop();
|
||||||
|
void handleAPIDBCUpload();
|
||||||
|
|
||||||
|
void handleAPITimeSync();
|
||||||
|
void handleAPIRestart();
|
||||||
|
void handleAPICANConfig();
|
||||||
|
void handleAPITriggerConfig();
|
||||||
|
void handleAPISignalAdd();
|
||||||
|
void handleAPISignalList();
|
||||||
|
|
||||||
|
void handleNotFound();
|
||||||
|
|
||||||
|
extern const char HTML_INDEX[];
|
||||||
|
extern const char HTML_SETTINGS[];
|
||||||
|
extern const char HTML_FILES[];
|
||||||
|
extern const char HTML_CAN[];
|
||||||
|
extern const char HTML_GRAPH[];
|
||||||
|
|
||||||
|
struct WiFiConfig {
|
||||||
|
char staSSID[32];
|
||||||
|
char staPassword[64];
|
||||||
|
bool useSTA;
|
||||||
|
};
|
||||||
|
|
||||||
|
extern WiFiConfig wifiConfig;
|
||||||
|
|
||||||
|
bool loadWiFiConfig();
|
||||||
|
bool saveWiFiConfig();
|
||||||
|
|
||||||
|
#endif // WEB_SERVER_H
|
||||||
433
web_settings.h
Normal file
433
web_settings.h
Normal file
@@ -0,0 +1,433 @@
|
|||||||
|
#ifndef WEB_SETTINGS_H
|
||||||
|
#define WEB_SETTINGS_H
|
||||||
|
|
||||||
|
const char HTML_SETTINGS[] = R"rawliteral(
|
||||||
|
<!DOCTYPE html>
|
||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta charset="UTF-8">
|
||||||
|
<meta name="viewport" content="width=device-width, initial-scale=1.0">
|
||||||
|
<title>Settings - ESP32 Logger</title>
|
||||||
|
<style>
|
||||||
|
* { margin: 0; padding: 0; box-sizing: border-box; }
|
||||||
|
body {
|
||||||
|
font-family: -apple-system, BlinkMacSystemFont, 'Segoe UI', Roboto, sans-serif;
|
||||||
|
background: #1a1a2e;
|
||||||
|
color: #eee;
|
||||||
|
line-height: 1.6;
|
||||||
|
}
|
||||||
|
.header {
|
||||||
|
background: #16213e;
|
||||||
|
padding: 1rem;
|
||||||
|
text-align: center;
|
||||||
|
border-bottom: 2px solid #e94560;
|
||||||
|
}
|
||||||
|
.header h1 { color: #e94560; font-size: 1.5rem; }
|
||||||
|
.nav {
|
||||||
|
background: #0f3460;
|
||||||
|
padding: 0.5rem;
|
||||||
|
display: flex;
|
||||||
|
justify-content: center;
|
||||||
|
flex-wrap: wrap;
|
||||||
|
gap: 0.5rem;
|
||||||
|
}
|
||||||
|
.nav a {
|
||||||
|
color: #fff;
|
||||||
|
text-decoration: none;
|
||||||
|
padding: 0.5rem 1rem;
|
||||||
|
border-radius: 4px;
|
||||||
|
transition: background 0.3s;
|
||||||
|
}
|
||||||
|
.nav a:hover, .nav a.active { background: #e94560; }
|
||||||
|
.container {
|
||||||
|
max-width: 800px;
|
||||||
|
margin: 0 auto;
|
||||||
|
padding: 2rem;
|
||||||
|
}
|
||||||
|
.settings-card {
|
||||||
|
background: #16213e;
|
||||||
|
padding: 2rem;
|
||||||
|
border-radius: 8px;
|
||||||
|
margin-bottom: 1rem;
|
||||||
|
}
|
||||||
|
.settings-card h2 {
|
||||||
|
color: #e94560;
|
||||||
|
margin-bottom: 1.5rem;
|
||||||
|
}
|
||||||
|
.form-group {
|
||||||
|
margin-bottom: 1.5rem;
|
||||||
|
}
|
||||||
|
.form-group label {
|
||||||
|
display: block;
|
||||||
|
margin-bottom: 0.5rem;
|
||||||
|
color: #00d9ff;
|
||||||
|
}
|
||||||
|
.form-group input, .form-group select {
|
||||||
|
width: 100%;
|
||||||
|
padding: 0.75rem;
|
||||||
|
background: #0f3460;
|
||||||
|
border: 1px solid #e94560;
|
||||||
|
color: #fff;
|
||||||
|
border-radius: 4px;
|
||||||
|
font-size: 1rem;
|
||||||
|
}
|
||||||
|
.form-group input:focus {
|
||||||
|
outline: none;
|
||||||
|
border-color: #00d9ff;
|
||||||
|
}
|
||||||
|
.btn {
|
||||||
|
background: #e94560;
|
||||||
|
color: #fff;
|
||||||
|
border: none;
|
||||||
|
padding: 1rem 2rem;
|
||||||
|
font-size: 1rem;
|
||||||
|
border-radius: 4px;
|
||||||
|
cursor: pointer;
|
||||||
|
transition: background 0.3s;
|
||||||
|
width: 100%;
|
||||||
|
}
|
||||||
|
.btn:hover { background: #ff6b6b; }
|
||||||
|
.btn-green { background: #00d9ff; color: #000; }
|
||||||
|
.btn-green:hover { background: #00b8d4; }
|
||||||
|
.status-box {
|
||||||
|
background: #0f3460;
|
||||||
|
padding: 1rem;
|
||||||
|
border-radius: 4px;
|
||||||
|
margin-bottom: 1rem;
|
||||||
|
}
|
||||||
|
.status-row {
|
||||||
|
display: flex;
|
||||||
|
justify-content: space-between;
|
||||||
|
padding: 0.5rem 0;
|
||||||
|
border-bottom: 1px solid #1a1a2e;
|
||||||
|
}
|
||||||
|
.status-row:last-child { border-bottom: none; }
|
||||||
|
.status-label { color: #aaa; }
|
||||||
|
.status-value { color: #00d9ff; }
|
||||||
|
.checkbox-group {
|
||||||
|
display: flex;
|
||||||
|
align-items: center;
|
||||||
|
gap: 0.5rem;
|
||||||
|
}
|
||||||
|
.checkbox-group input[type="checkbox"] {
|
||||||
|
width: 20px;
|
||||||
|
height: 20px;
|
||||||
|
}
|
||||||
|
.row {
|
||||||
|
display: flex;
|
||||||
|
gap: 0.5rem;
|
||||||
|
flex-wrap: wrap;
|
||||||
|
}
|
||||||
|
.row input, .row select {
|
||||||
|
flex: 1;
|
||||||
|
min-width: 80px;
|
||||||
|
}
|
||||||
|
</style>
|
||||||
|
</head>
|
||||||
|
<body>
|
||||||
|
<div class="header">
|
||||||
|
<h1>Settings</h1>
|
||||||
|
</div>
|
||||||
|
<nav class="nav">
|
||||||
|
<a href="/">Dashboard</a>
|
||||||
|
<a href="/graph">Graph</a>
|
||||||
|
<a href="/files">Files</a>
|
||||||
|
<a href="/can">CAN Transmit</a>
|
||||||
|
<a href="/settings" class="active">Settings</a>
|
||||||
|
</nav>
|
||||||
|
<div class="container">
|
||||||
|
<div class="settings-card">
|
||||||
|
<h2>CAN Configuration</h2>
|
||||||
|
<div class="status-box">
|
||||||
|
<div class="status-row">
|
||||||
|
<span class="status-label">CAN Status:</span>
|
||||||
|
<span class="status-value" id="canStatus">Active</span>
|
||||||
|
</div>
|
||||||
|
<div class="status-row">
|
||||||
|
<span class="status-label">Current Mode:</span>
|
||||||
|
<span class="status-value" id="currentCANMode">Normal</span>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<form id="canForm" onsubmit="saveCANConfig(event)">
|
||||||
|
<div class="form-group">
|
||||||
|
<label>CAN Type</label>
|
||||||
|
<select id="canType" onchange="toggleCANFDOptions()">
|
||||||
|
<option value="fd">CAN FD (up to 64 bytes, flexible data rate)</option>
|
||||||
|
<option value="classic">Classic CAN (8 bytes, fixed rate)</option>
|
||||||
|
</select>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="row">
|
||||||
|
<div class="form-group">
|
||||||
|
<label>Arbitration Baud</label>
|
||||||
|
<select id="arbBaud">
|
||||||
|
<option value="125000">125 kbps</option>
|
||||||
|
<option value="250000">250 kbps</option>
|
||||||
|
<option value="500000" selected>500 kbps</option>
|
||||||
|
<option value="1000000">1 Mbps</option>
|
||||||
|
</select>
|
||||||
|
</div>
|
||||||
|
<div class="form-group" id="dataBaudGroup">
|
||||||
|
<label>Data Baud (CAN FD only)</label>
|
||||||
|
<select id="dataBaud">
|
||||||
|
<option value="1000000">1 Mbps</option>
|
||||||
|
<option value="2000000" selected>2 Mbps</option>
|
||||||
|
<option value="4000000">4 Mbps</option>
|
||||||
|
<option value="8000000">8 Mbps</option>
|
||||||
|
</select>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="form-group">
|
||||||
|
<label>CAN Mode</label>
|
||||||
|
<select id="canMode">
|
||||||
|
<option value="0">Normal</option>
|
||||||
|
<option value="1">Listen Only</option>
|
||||||
|
<option value="2">Loopback</option>
|
||||||
|
</select>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<button type="submit" class="btn">Apply CAN Settings</button>
|
||||||
|
</form>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="settings-card">
|
||||||
|
<h2>Signal Configuration</h2>
|
||||||
|
<div class="form-group">
|
||||||
|
<label>Manual Signal Definition</label>
|
||||||
|
<div class="row">
|
||||||
|
<input type="text" id="sigName" placeholder="Signal Name" style="flex:1">
|
||||||
|
<input type="text" id="sigCanId" placeholder="CAN ID (hex)" style="width:100px">
|
||||||
|
</div>
|
||||||
|
<div class="row" style="margin-top:0.5rem">
|
||||||
|
<input type="number" id="sigStartBit" placeholder="Start Bit" style="width:80px">
|
||||||
|
<input type="number" id="sigLength" placeholder="Length" style="width:80px">
|
||||||
|
<input type="number" id="sigFactor" placeholder="Factor" value="1" style="width:80px">
|
||||||
|
<input type="number" id="sigOffset" placeholder="Offset" value="0" style="width:80px">
|
||||||
|
</div>
|
||||||
|
<button class="btn" style="margin-top:1rem" onclick="addSignal()">Add Signal</button>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="form-group">
|
||||||
|
<label>Upload DBC File</label>
|
||||||
|
<input type="file" id="dbcFile" accept=".dbc" onchange="uploadDBC()">
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="settings-card">
|
||||||
|
<h2>WiFi Configuration</h2>
|
||||||
|
<div class="status-box">
|
||||||
|
<div class="status-row">
|
||||||
|
<span class="status-label">Current Mode:</span>
|
||||||
|
<span class="status-value" id="currentMode">AP Mode</span>
|
||||||
|
</div>
|
||||||
|
<div class="status-row">
|
||||||
|
<span class="status-label">AP IP:</span>
|
||||||
|
<span class="status-value" id="apIP">192.168.4.1</span>
|
||||||
|
</div>
|
||||||
|
<div class="status-row">
|
||||||
|
<span class="status-label">STA IP:</span>
|
||||||
|
<span class="status-value" id="staIP">Not connected</span>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<form id="wifiForm" onsubmit="saveWiFi(event)">
|
||||||
|
<div class="form-group checkbox-group">
|
||||||
|
<input type="checkbox" id="enableSTA" onchange="toggleSTA()">
|
||||||
|
<label for="enableSTA" style="margin-bottom: 0;">Enable STA Mode (Connect to existing WiFi)</label>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div id="staConfig" style="display: none;">
|
||||||
|
<div class="form-group">
|
||||||
|
<label>WiFi SSID</label>
|
||||||
|
<input type="text" id="ssid" placeholder="Your WiFi Network">
|
||||||
|
</div>
|
||||||
|
<div class="form-group">
|
||||||
|
<label>WiFi Password</label>
|
||||||
|
<input type="password" id="password" placeholder="WiFi Password">
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<button type="submit" class="btn">Save WiFi Settings</button>
|
||||||
|
</form>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="settings-card">
|
||||||
|
<h2>Time Settings</h2>
|
||||||
|
<div class="status-box">
|
||||||
|
<div class="status-row">
|
||||||
|
<span class="status-label">Current Time:</span>
|
||||||
|
<span class="status-value" id="currentTime">--</span>
|
||||||
|
</div>
|
||||||
|
<div class="status-row">
|
||||||
|
<span class="status-label">RTC Status:</span>
|
||||||
|
<span class="status-value" id="rtcStatus">OK</span>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<button class="btn btn-green" onclick="syncTime()">Sync Time from Device</button>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="settings-card">
|
||||||
|
<h2>System</h2>
|
||||||
|
<button class="btn" onclick="restartSystem()">Restart System</button>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<script>
|
||||||
|
function toggleCANFDOptions() {
|
||||||
|
const canType = document.getElementById('canType').value;
|
||||||
|
const dataBaudGroup = document.getElementById('dataBaudGroup');
|
||||||
|
if (canType === 'classic') {
|
||||||
|
dataBaudGroup.style.opacity = '0.5';
|
||||||
|
dataBaudGroup.style.pointerEvents = 'none';
|
||||||
|
} else {
|
||||||
|
dataBaudGroup.style.opacity = '1';
|
||||||
|
dataBaudGroup.style.pointerEvents = 'auto';
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
function toggleSTA() {
|
||||||
|
const enabled = document.getElementById('enableSTA').checked;
|
||||||
|
document.getElementById('staConfig').style.display = enabled ? 'block' : 'none';
|
||||||
|
}
|
||||||
|
|
||||||
|
function saveWiFi(event) {
|
||||||
|
event.preventDefault();
|
||||||
|
|
||||||
|
const config = {
|
||||||
|
enableSTA: document.getElementById('enableSTA').checked,
|
||||||
|
ssid: document.getElementById('ssid').value,
|
||||||
|
password: document.getElementById('password').value
|
||||||
|
};
|
||||||
|
|
||||||
|
fetch('/api/wifi', {
|
||||||
|
method: 'POST',
|
||||||
|
headers: {'Content-Type': 'application/json'},
|
||||||
|
body: JSON.stringify(config)
|
||||||
|
})
|
||||||
|
.then(() => alert('WiFi settings saved. System will restart.'));
|
||||||
|
}
|
||||||
|
|
||||||
|
function saveCANConfig(event) {
|
||||||
|
event.preventDefault();
|
||||||
|
|
||||||
|
const canType = document.getElementById('canType').value;
|
||||||
|
const config = {
|
||||||
|
arbBaud: parseInt(document.getElementById('arbBaud').value),
|
||||||
|
dataBaud: canType === 'fd' ? parseInt(document.getElementById('dataBaud').value) : parseInt(document.getElementById('arbBaud').value),
|
||||||
|
mode: parseInt(document.getElementById('canMode').value),
|
||||||
|
enableFD: canType === 'fd'
|
||||||
|
};
|
||||||
|
|
||||||
|
fetch('/api/can/config', {
|
||||||
|
method: 'POST',
|
||||||
|
headers: {'Content-Type': 'application/json'},
|
||||||
|
body: JSON.stringify(config)
|
||||||
|
})
|
||||||
|
.then(r => r.json())
|
||||||
|
.then(data => {
|
||||||
|
alert('CAN settings applied!');
|
||||||
|
loadStatus();
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
function addSignal() {
|
||||||
|
const name = document.getElementById('sigName').value;
|
||||||
|
const canId = parseInt(document.getElementById('sigCanId').value, 16);
|
||||||
|
const startBit = parseInt(document.getElementById('sigStartBit').value);
|
||||||
|
const length = parseInt(document.getElementById('sigLength').value);
|
||||||
|
const factor = parseFloat(document.getElementById('sigFactor').value) || 1;
|
||||||
|
const offset = parseFloat(document.getElementById('sigOffset').value) || 0;
|
||||||
|
|
||||||
|
if (!name || isNaN(canId)) {
|
||||||
|
alert('Please enter signal name and CAN ID');
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
fetch('/api/signal/add', {
|
||||||
|
method: 'POST',
|
||||||
|
headers: {'Content-Type': 'application/json'},
|
||||||
|
body: JSON.stringify({
|
||||||
|
name: name,
|
||||||
|
canId: canId,
|
||||||
|
startBit: startBit || 0,
|
||||||
|
length: length || 8,
|
||||||
|
factor: factor,
|
||||||
|
offset: offset,
|
||||||
|
littleEndian: true,
|
||||||
|
signed: false
|
||||||
|
})
|
||||||
|
})
|
||||||
|
.then(r => r.json())
|
||||||
|
.then(data => {
|
||||||
|
alert('Signal added!');
|
||||||
|
document.getElementById('sigName').value = '';
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
function uploadDBC() {
|
||||||
|
const file = document.getElementById('dbcFile').files[0];
|
||||||
|
if (!file) return;
|
||||||
|
|
||||||
|
const reader = new FileReader();
|
||||||
|
reader.onload = function(e) {
|
||||||
|
fetch('/api/dbc/upload', {
|
||||||
|
method: 'POST',
|
||||||
|
headers: {'Content-Type': 'text/plain'},
|
||||||
|
body: e.target.result
|
||||||
|
})
|
||||||
|
.then(r => r.json())
|
||||||
|
.then(data => {
|
||||||
|
if (data.status === 'loaded') {
|
||||||
|
alert('DBC file loaded successfully!');
|
||||||
|
} else {
|
||||||
|
alert('Failed to load DBC: ' + data.error);
|
||||||
|
}
|
||||||
|
});
|
||||||
|
};
|
||||||
|
reader.readAsText(file);
|
||||||
|
}
|
||||||
|
|
||||||
|
function syncTime() {
|
||||||
|
const now = new Date();
|
||||||
|
const timestamp = Math.floor(now.getTime() / 1000);
|
||||||
|
|
||||||
|
fetch('/api/time', {
|
||||||
|
method: 'POST',
|
||||||
|
headers: {'Content-Type': 'application/json'},
|
||||||
|
body: JSON.stringify({timestamp: timestamp})
|
||||||
|
})
|
||||||
|
.then(() => {
|
||||||
|
alert('Time synchronized!');
|
||||||
|
loadStatus();
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
function restartSystem() {
|
||||||
|
if (!confirm('Restart the system?')) return;
|
||||||
|
fetch('/api/restart', {method: 'POST'});
|
||||||
|
}
|
||||||
|
|
||||||
|
function loadStatus() {
|
||||||
|
fetch('/api/status')
|
||||||
|
.then(r => r.json())
|
||||||
|
.then(data => {
|
||||||
|
document.getElementById('currentMode').textContent =
|
||||||
|
data.ap && data.sta ? 'AP+STA' : (data.ap ? 'AP' : 'STA');
|
||||||
|
document.getElementById('apIP').textContent = data.ap_ip || 'N/A';
|
||||||
|
document.getElementById('staIP').textContent = data.sta_ip || 'Not connected';
|
||||||
|
document.getElementById('canStatus').textContent = data.can.initialized ? 'Active' : 'Inactive';
|
||||||
|
});
|
||||||
|
|
||||||
|
document.getElementById('currentTime').textContent = new Date().toLocaleString();
|
||||||
|
}
|
||||||
|
|
||||||
|
loadStatus();
|
||||||
|
setInterval(loadStatus, 30000);
|
||||||
|
</script>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
|
)rawliteral";
|
||||||
|
|
||||||
|
#endif // WEB_SETTINGS_H
|
||||||
421
web_test.h
Normal file
421
web_test.h
Normal file
@@ -0,0 +1,421 @@
|
|||||||
|
#ifndef WEB_TEST_H
|
||||||
|
#define WEB_TEST_H
|
||||||
|
|
||||||
|
const char HTML_TEST[] = R"rawliteral(
|
||||||
|
<!DOCTYPE html>
|
||||||
|
<html>
|
||||||
|
<head>
|
||||||
|
<meta charset="UTF-8">
|
||||||
|
<meta name="viewport" content="width=device-width, initial-scale=1.0">
|
||||||
|
<title>Hardware Test - ESP32 CAN FD Logger</title>
|
||||||
|
<style>
|
||||||
|
* { margin: 0; padding: 0; box-sizing: border-box; }
|
||||||
|
body {
|
||||||
|
font-family: -apple-system, BlinkMacSystemFont, 'Segoe UI', Roboto, sans-serif;
|
||||||
|
background: #1a1a2e;
|
||||||
|
color: #eee;
|
||||||
|
line-height: 1.6;
|
||||||
|
}
|
||||||
|
.header {
|
||||||
|
background: #16213e;
|
||||||
|
padding: 1rem;
|
||||||
|
text-align: center;
|
||||||
|
border-bottom: 2px solid #e94560;
|
||||||
|
}
|
||||||
|
.header h1 { color: #e94560; font-size: 1.5rem; }
|
||||||
|
.nav {
|
||||||
|
background: #0f3460;
|
||||||
|
padding: 0.5rem;
|
||||||
|
display: flex;
|
||||||
|
justify-content: center;
|
||||||
|
flex-wrap: wrap;
|
||||||
|
gap: 0.5rem;
|
||||||
|
}
|
||||||
|
.nav a {
|
||||||
|
color: #fff;
|
||||||
|
text-decoration: none;
|
||||||
|
padding: 0.5rem 1rem;
|
||||||
|
border-radius: 4px;
|
||||||
|
transition: background 0.3s;
|
||||||
|
}
|
||||||
|
.nav a:hover, .nav a.active { background: #e94560; }
|
||||||
|
.container {
|
||||||
|
max-width: 1000px;
|
||||||
|
margin: 0 auto;
|
||||||
|
padding: 2rem;
|
||||||
|
}
|
||||||
|
.test-card {
|
||||||
|
background: #16213e;
|
||||||
|
padding: 1.5rem;
|
||||||
|
border-radius: 8px;
|
||||||
|
margin-bottom: 1rem;
|
||||||
|
}
|
||||||
|
.test-card h2 { color: #e94560; margin-bottom: 1rem; }
|
||||||
|
.test-grid {
|
||||||
|
display: grid;
|
||||||
|
grid-template-columns: repeat(auto-fit, minmax(250px, 1fr));
|
||||||
|
gap: 1rem;
|
||||||
|
margin-bottom: 1rem;
|
||||||
|
}
|
||||||
|
.test-item {
|
||||||
|
background: #0f3460;
|
||||||
|
padding: 1rem;
|
||||||
|
border-radius: 8px;
|
||||||
|
text-align: center;
|
||||||
|
}
|
||||||
|
.test-item h3 { color: #00d9ff; margin-bottom: 0.5rem; }
|
||||||
|
.test-item p { font-size: 0.875rem; color: #aaa; margin-bottom: 1rem; }
|
||||||
|
.btn {
|
||||||
|
background: #e94560;
|
||||||
|
color: #fff;
|
||||||
|
border: none;
|
||||||
|
padding: 0.75rem 1.5rem;
|
||||||
|
border-radius: 4px;
|
||||||
|
cursor: pointer;
|
||||||
|
transition: background 0.3s;
|
||||||
|
font-size: 1rem;
|
||||||
|
}
|
||||||
|
.btn:hover { background: #ff6b6b; }
|
||||||
|
.btn:disabled { background: #666; cursor: not-allowed; }
|
||||||
|
.btn-green { background: #00d9ff; color: #000; }
|
||||||
|
.btn-green:hover { background: #00b8d4; }
|
||||||
|
.form-group {
|
||||||
|
margin-bottom: 1rem;
|
||||||
|
}
|
||||||
|
.form-group label {
|
||||||
|
display: block;
|
||||||
|
margin-bottom: 0.5rem;
|
||||||
|
color: #00d9ff;
|
||||||
|
}
|
||||||
|
.form-group input, .form-group select {
|
||||||
|
width: 100%;
|
||||||
|
padding: 0.75rem;
|
||||||
|
background: #0f3460;
|
||||||
|
border: 1px solid #e94560;
|
||||||
|
color: #fff;
|
||||||
|
border-radius: 4px;
|
||||||
|
}
|
||||||
|
.row {
|
||||||
|
display: flex;
|
||||||
|
gap: 1rem;
|
||||||
|
flex-wrap: wrap;
|
||||||
|
}
|
||||||
|
.row > * { flex: 1; min-width: 150px; }
|
||||||
|
.result-box {
|
||||||
|
background: #0f3460;
|
||||||
|
padding: 1rem;
|
||||||
|
border-radius: 8px;
|
||||||
|
margin-top: 1rem;
|
||||||
|
}
|
||||||
|
.result-row {
|
||||||
|
display: flex;
|
||||||
|
justify-content: space-between;
|
||||||
|
padding: 0.5rem 0;
|
||||||
|
border-bottom: 1px solid #1a1a2e;
|
||||||
|
}
|
||||||
|
.result-row:last-child { border-bottom: none; }
|
||||||
|
.result-label { color: #aaa; }
|
||||||
|
.result-value { color: #00d9ff; font-weight: bold; }
|
||||||
|
.result-value.pass { color: #2ecc71; }
|
||||||
|
.result-value.fail { color: #e74c3c; }
|
||||||
|
.status-running {
|
||||||
|
animation: pulse 1s infinite;
|
||||||
|
}
|
||||||
|
@keyframes pulse {
|
||||||
|
0%, 100% { opacity: 1; }
|
||||||
|
50% { opacity: 0.5; }
|
||||||
|
}
|
||||||
|
.log {
|
||||||
|
background: #0f3460;
|
||||||
|
padding: 1rem;
|
||||||
|
border-radius: 8px;
|
||||||
|
height: 150px;
|
||||||
|
overflow-y: auto;
|
||||||
|
font-family: monospace;
|
||||||
|
font-size: 0.875rem;
|
||||||
|
margin-top: 1rem;
|
||||||
|
}
|
||||||
|
</style>
|
||||||
|
</head>
|
||||||
|
<body>
|
||||||
|
<div class="header">
|
||||||
|
<h1>Hardware Test</h1>
|
||||||
|
</div>
|
||||||
|
<nav class="nav">
|
||||||
|
<a href="/">Dashboard</a>
|
||||||
|
<a href="/graph">Graph</a>
|
||||||
|
<a href="/files">Files</a>
|
||||||
|
<a href="/can">CAN Transmit</a>
|
||||||
|
<a href="/settings">Settings</a>
|
||||||
|
<a href="/test" class="active">Test</a>
|
||||||
|
</nav>
|
||||||
|
<div class="container">
|
||||||
|
<div class="test-card">
|
||||||
|
<h2>CAN FD Loopback Test</h2>
|
||||||
|
<p style="margin-bottom:1rem;color:#aaa">Tests internal CAN controller by sending frames in loopback mode.</p>
|
||||||
|
|
||||||
|
<div class="row">
|
||||||
|
<div class="form-group">
|
||||||
|
<label>Frame Count</label>
|
||||||
|
<input type="number" id="loopbackFrames" value="1000" min="10" max="10000">
|
||||||
|
</div>
|
||||||
|
<div class="form-group">
|
||||||
|
<label>Interval (μs)</label>
|
||||||
|
<input type="number" id="loopbackInterval" value="1000" min="0" max="100000">
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<button class="btn" onclick="startLoopbackTest()">Start Loopback Test</button>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="test-card">
|
||||||
|
<h2>CAN FD Stress Test</h2>
|
||||||
|
<p style="margin-bottom:1rem;color:#aaa">Tests maximum throughput with continuous frame transmission.</p>
|
||||||
|
|
||||||
|
<div class="row">
|
||||||
|
<div class="form-group">
|
||||||
|
<label>Frame Count</label>
|
||||||
|
<input type="number" id="stressFrames" value="5000" min="100" max="50000">
|
||||||
|
</div>
|
||||||
|
<div class="form-group">
|
||||||
|
<label>Data Length</label>
|
||||||
|
<select id="stressDataLen">
|
||||||
|
<option value="8">8 bytes (Classic)</option>
|
||||||
|
<option value="16">16 bytes (FD)</option>
|
||||||
|
<option value="32">32 bytes (FD)</option>
|
||||||
|
<option value="64" selected>64 bytes (FD)</option>
|
||||||
|
</select>
|
||||||
|
</div>
|
||||||
|
<div class="form-group">
|
||||||
|
<label>CAN FD Mode</label>
|
||||||
|
<select id="stressUseFD">
|
||||||
|
<option value="true" selected>CAN FD</option>
|
||||||
|
<option value="false">Classic CAN</option>
|
||||||
|
</select>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<button class="btn" onclick="startStressTest()">Start Stress Test</button>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="test-card">
|
||||||
|
<h2>Sequence Test</h2>
|
||||||
|
<p style="margin-bottom:1rem;color:#aaa">Tests frame ordering and loss detection with sequence numbers.</p>
|
||||||
|
|
||||||
|
<div class="row">
|
||||||
|
<div class="form-group">
|
||||||
|
<label>Frame Count</label>
|
||||||
|
<input type="number" id="seqFrames" value="2000" min="100" max="20000">
|
||||||
|
</div>
|
||||||
|
<div class="form-group">
|
||||||
|
<label>CAN ID (hex)</label>
|
||||||
|
<input type="text" id="seqCanId" value="0x100">
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
<button class="btn" onclick="startSequenceTest()">Start Sequence Test</button>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="test-card">
|
||||||
|
<h2>Test Results</h2>
|
||||||
|
<div style="display:flex;gap:1rem;margin-bottom:1rem;">
|
||||||
|
<button class="btn btn-green" onclick="getTestStatus()">Refresh Status</button>
|
||||||
|
<button class="btn" onclick="stopTest()" id="btnStop" disabled>Stop Test</button>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="result-box" id="testResults">
|
||||||
|
<div class="result-row">
|
||||||
|
<span class="result-label">Status:</span>
|
||||||
|
<span class="result-value" id="resStatus">Idle</span>
|
||||||
|
</div>
|
||||||
|
<div class="result-row">
|
||||||
|
<span class="result-label">Frames Sent:</span>
|
||||||
|
<span class="result-value" id="resSent">0</span>
|
||||||
|
</div>
|
||||||
|
<div class="result-row">
|
||||||
|
<span class="result-label">Frames Received:</span>
|
||||||
|
<span class="result-value" id="resReceived">0</span>
|
||||||
|
</div>
|
||||||
|
<div class="result-row">
|
||||||
|
<span class="result-label">Frames Lost:</span>
|
||||||
|
<span class="result-value" id="resLost">0</span>
|
||||||
|
</div>
|
||||||
|
<div class="result-row">
|
||||||
|
<span class="result-label">Frame Rate:</span>
|
||||||
|
<span class="result-value" id="resRate">0 fps</span>
|
||||||
|
</div>
|
||||||
|
<div class="result-row">
|
||||||
|
<span class="result-label">Loss Rate:</span>
|
||||||
|
<span class="result-value" id="resLossRate">0%</span>
|
||||||
|
</div>
|
||||||
|
<div class="result-row">
|
||||||
|
<span class="result-label">Duration:</span>
|
||||||
|
<span class="result-value" id="resDuration">0 ms</span>
|
||||||
|
</div>
|
||||||
|
<div class="result-row">
|
||||||
|
<span class="result-label">Result:</span>
|
||||||
|
<span class="result-value" id="resPass">-</span>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<div class="log" id="testLog"></div>
|
||||||
|
</div>
|
||||||
|
</div>
|
||||||
|
|
||||||
|
<script>
|
||||||
|
let testRunning = false;
|
||||||
|
let pollInterval = null;
|
||||||
|
|
||||||
|
function log(msg) {
|
||||||
|
const logDiv = document.getElementById('testLog');
|
||||||
|
const entry = document.createElement('div');
|
||||||
|
entry.textContent = new Date().toLocaleTimeString() + ' - ' + msg;
|
||||||
|
logDiv.appendChild(entry);
|
||||||
|
logDiv.scrollTop = logDiv.scrollHeight;
|
||||||
|
}
|
||||||
|
|
||||||
|
function startLoopbackTest() {
|
||||||
|
const frames = parseInt(document.getElementById('loopbackFrames').value);
|
||||||
|
const interval = parseInt(document.getElementById('loopbackInterval').value);
|
||||||
|
|
||||||
|
fetch('/api/test/start', {
|
||||||
|
method: 'POST',
|
||||||
|
headers: {'Content-Type': 'application/json'},
|
||||||
|
body: JSON.stringify({
|
||||||
|
type: 'loopback',
|
||||||
|
frames: frames,
|
||||||
|
interval: interval
|
||||||
|
})
|
||||||
|
})
|
||||||
|
.then(r => r.json())
|
||||||
|
.then(data => {
|
||||||
|
if (data.status === 'started') {
|
||||||
|
log('Loopback test started: ' + frames + ' frames');
|
||||||
|
testRunning = true;
|
||||||
|
startPolling();
|
||||||
|
} else {
|
||||||
|
log('Error: ' + data.error);
|
||||||
|
}
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
function startStressTest() {
|
||||||
|
const frames = parseInt(document.getElementById('stressFrames').value);
|
||||||
|
const dataLen = parseInt(document.getElementById('stressDataLen').value);
|
||||||
|
const useFD = document.getElementById('stressUseFD').value === 'true';
|
||||||
|
|
||||||
|
fetch('/api/test/start', {
|
||||||
|
method: 'POST',
|
||||||
|
headers: {'Content-Type': 'application/json'},
|
||||||
|
body: JSON.stringify({
|
||||||
|
type: 'stress',
|
||||||
|
frames: frames,
|
||||||
|
dataLen: dataLen,
|
||||||
|
useFD: useFD
|
||||||
|
})
|
||||||
|
})
|
||||||
|
.then(r => r.json())
|
||||||
|
.then(data => {
|
||||||
|
if (data.status === 'started') {
|
||||||
|
log('Stress test started: ' + frames + ' frames, ' + dataLen + ' bytes');
|
||||||
|
testRunning = true;
|
||||||
|
startPolling();
|
||||||
|
} else {
|
||||||
|
log('Error: ' + data.error);
|
||||||
|
}
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
function startSequenceTest() {
|
||||||
|
const frames = parseInt(document.getElementById('seqFrames').value);
|
||||||
|
const canId = parseInt(document.getElementById('seqCanId').value, 16);
|
||||||
|
|
||||||
|
fetch('/api/test/start', {
|
||||||
|
method: 'POST',
|
||||||
|
headers: {'Content-Type': 'application/json'},
|
||||||
|
body: JSON.stringify({
|
||||||
|
type: 'sequence',
|
||||||
|
frames: frames,
|
||||||
|
canId: canId
|
||||||
|
})
|
||||||
|
})
|
||||||
|
.then(r => r.json())
|
||||||
|
.then(data => {
|
||||||
|
if (data.status === 'started') {
|
||||||
|
log('Sequence test started: ' + frames + ' frames, ID=0x' + canId.toString(16));
|
||||||
|
testRunning = true;
|
||||||
|
startPolling();
|
||||||
|
} else {
|
||||||
|
log('Error: ' + data.error);
|
||||||
|
}
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
function stopTest() {
|
||||||
|
fetch('/api/test/stop', {method: 'POST'})
|
||||||
|
.then(() => {
|
||||||
|
log('Test stopped');
|
||||||
|
testRunning = false;
|
||||||
|
stopPolling();
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
function getTestStatus() {
|
||||||
|
fetch('/api/test/status')
|
||||||
|
.then(r => r.json())
|
||||||
|
.then(data => {
|
||||||
|
updateResults(data);
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
function updateResults(data) {
|
||||||
|
document.getElementById('resStatus').textContent = data.running ? 'Running...' : 'Idle';
|
||||||
|
document.getElementById('resStatus').className = 'result-value' + (data.running ? ' status-running' : '');
|
||||||
|
|
||||||
|
if (data.result) {
|
||||||
|
document.getElementById('resSent').textContent = data.result.framesSent;
|
||||||
|
document.getElementById('resReceived').textContent = data.result.framesReceived;
|
||||||
|
document.getElementById('resLost').textContent = data.result.framesLost;
|
||||||
|
document.getElementById('resRate').textContent = data.result.frameRate.toFixed(1) + ' fps';
|
||||||
|
document.getElementById('resLossRate').textContent = data.result.lossRate.toFixed(2) + '%';
|
||||||
|
document.getElementById('resDuration').textContent = data.result.durationMs + ' ms';
|
||||||
|
|
||||||
|
const passEl = document.getElementById('resPass');
|
||||||
|
if (data.result.passed) {
|
||||||
|
passEl.textContent = 'PASS';
|
||||||
|
passEl.className = 'result-value pass';
|
||||||
|
} else if (data.result.framesSent > 0) {
|
||||||
|
passEl.textContent = 'FAIL';
|
||||||
|
passEl.className = 'result-value fail';
|
||||||
|
} else {
|
||||||
|
passEl.textContent = '-';
|
||||||
|
passEl.className = 'result-value';
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
document.getElementById('btnStop').disabled = !data.running;
|
||||||
|
|
||||||
|
if (!data.running && testRunning) {
|
||||||
|
testRunning = false;
|
||||||
|
stopPolling();
|
||||||
|
log('Test completed');
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
function startPolling() {
|
||||||
|
if (pollInterval) clearInterval(pollInterval);
|
||||||
|
pollInterval = setInterval(getTestStatus, 500);
|
||||||
|
}
|
||||||
|
|
||||||
|
function stopPolling() {
|
||||||
|
if (pollInterval) {
|
||||||
|
clearInterval(pollInterval);
|
||||||
|
pollInterval = null;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
getTestStatus();
|
||||||
|
log('Test page loaded');
|
||||||
|
</script>
|
||||||
|
</body>
|
||||||
|
</html>
|
||||||
|
)rawliteral";
|
||||||
|
|
||||||
|
#endif // WEB_TEST_H
|
||||||
Reference in New Issue
Block a user