Compare commits
22 Commits
5cb0be0aaa
...
master
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
a46496d688 | ||
|
|
47b3427e63 | ||
|
|
12a0d58800 | ||
| 629c735eec | |||
|
|
992270ed00 | ||
|
|
83af09b47c | ||
|
|
0c342d7989 | ||
|
|
58a523aab2 | ||
|
|
896ba322c0 | ||
|
|
9173c3b93a | ||
|
|
f2c69587ee | ||
|
|
324cd5dddc | ||
|
|
bc53bd7e82 | ||
|
|
477fd698dc | ||
|
|
7301149c47 | ||
|
|
b7cf38c649 | ||
|
|
ceb9610bca | ||
|
|
7d8f813b59 | ||
|
|
8044bbde94 | ||
|
|
4a830dde91 | ||
|
|
64ce2472ab | ||
|
|
952a42b3e9 |
5
IDEAS.md
Normal file
5
IDEAS.md
Normal file
@@ -0,0 +1,5 @@
|
|||||||
|
Note to keep inspirations lest I forget.
|
||||||
|
|
||||||
|
# Things to do, but not really urgent
|
||||||
|
- Fit OpenStreetMap somewhere and have a proper map widget in UI (not really navs, just show where I am)
|
||||||
|
- Integrate paho-mqtt into Python backend for some telemetry. Also set up mosquitto or whatnots on vps.
|
||||||
@@ -88,7 +88,7 @@ void imu_init() {
|
|||||||
imu_send_cmd(0x65); // Flat mounting mode
|
imu_send_cmd(0x65); // Flat mounting mode
|
||||||
delay(50);
|
delay(50);
|
||||||
imu_send_cmd(0x64); // 9600 bauds / 20Hz report
|
imu_send_cmd(0x64); // 9600 bauds / 20Hz report
|
||||||
delay(150); // Let WT61 process config
|
delay(50); // Let WT61 process config
|
||||||
|
|
||||||
// Revert to 9600 bauds
|
// Revert to 9600 bauds
|
||||||
imuSerial.begin(9600);
|
imuSerial.begin(9600);
|
||||||
@@ -99,7 +99,7 @@ void imu_init() {
|
|||||||
imu_send_cmd(0x65); // Flat mounting mode
|
imu_send_cmd(0x65); // Flat mounting mode
|
||||||
delay(50);
|
delay(50);
|
||||||
imu_send_cmd(0x64); // 9600 bauds / 20Hz report
|
imu_send_cmd(0x64); // 9600 bauds / 20Hz report
|
||||||
delay(150); // Let WT61 process config
|
delay(50); // Let WT61 process config
|
||||||
|
|
||||||
|
|
||||||
rxIndex = 0;
|
rxIndex = 0;
|
||||||
|
|||||||
@@ -1,14 +1,14 @@
|
|||||||
{
|
{
|
||||||
"dark": {
|
"dark": {
|
||||||
"background": "#404040",
|
"background": "#303030",
|
||||||
"foreground": "#EAEAEA",
|
"foreground": "#EAEAEA",
|
||||||
"highlight": "#FA1504",
|
"highlight": "#FA1504",
|
||||||
"subdued": "#fda052"
|
"subdued": "#fda052"
|
||||||
},
|
},
|
||||||
"bright": {
|
"bright": {
|
||||||
"background": "#fda052",
|
"background": "#fda052",
|
||||||
"foreground": "#202020",
|
"foreground": "#303030",
|
||||||
"highlight": "#FB2E0A",
|
"highlight": "#df2100",
|
||||||
"subdued": "#EAEAEA"
|
"subdued": "#EAEAEA"
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -8,8 +8,12 @@ Python GPS and Arduino telemetry service for Smart Serow. Connects to `gpsd` and
|
|||||||
# Install uv if you haven't
|
# Install uv if you haven't
|
||||||
curl -LsSf https://astral.sh/uv/install.sh | sh
|
curl -LsSf https://astral.sh/uv/install.sh | sh
|
||||||
|
|
||||||
# Install dependencies
|
# Install system dependencies (GPIO)
|
||||||
|
sudo apt install python3-rpi.gpio
|
||||||
|
|
||||||
|
# Create venv with access to system packages, then sync
|
||||||
cd pi/backend
|
cd pi/backend
|
||||||
|
uv venv --system-site-packages
|
||||||
uv sync
|
uv sync
|
||||||
```
|
```
|
||||||
|
|
||||||
@@ -26,6 +30,8 @@ uv run flask --app main run --host 0.0.0.0 --port 5000 --reload
|
|||||||
|
|
||||||
## API
|
## API
|
||||||
|
|
||||||
|
### HTTP Endpoints
|
||||||
|
|
||||||
| Endpoint | Description |
|
| Endpoint | Description |
|
||||||
|----------|-------------|
|
|----------|-------------|
|
||||||
| `GET /health` | Health check, shows gpsd and Arduino connection status |
|
| `GET /health` | Health check, shows gpsd and Arduino connection status |
|
||||||
@@ -34,6 +40,34 @@ uv run flask --app main run --host 0.0.0.0 --port 5000 --reload
|
|||||||
| `GET /arduino` | Latest Arduino telemetry (voltage, rpm, eng_temp, gear) |
|
| `GET /arduino` | Latest Arduino telemetry (voltage, rpm, eng_temp, gear) |
|
||||||
| `GET /arduino/history` | Last 100 buffered Arduino readings |
|
| `GET /arduino/history` | Last 100 buffered Arduino readings |
|
||||||
|
|
||||||
|
### WebSocket Events (socket.io)
|
||||||
|
|
||||||
|
Real-time data is pushed over WebSocket. The UI connects once and receives streams.
|
||||||
|
|
||||||
|
**Server → Client:**
|
||||||
|
|
||||||
|
| Event | Description |
|
||||||
|
|-------|-------------|
|
||||||
|
| `arduino` | Real-time telemetry (voltage, rpm, roll, pitch, accel, etc.) |
|
||||||
|
| `gps` | GPS position updates |
|
||||||
|
| `status` | Connection status + `theme_switch` signal from GPIO |
|
||||||
|
| `alert` | System alerts |
|
||||||
|
| `ack` | Command acknowledgments |
|
||||||
|
|
||||||
|
**Client → Server:**
|
||||||
|
|
||||||
|
| Event | Description |
|
||||||
|
|-------|-------------|
|
||||||
|
| `button` | UI button presses (horn, light, indicators, hazard) |
|
||||||
|
| `emergency` | Emergency signal |
|
||||||
|
|
||||||
|
### Throttling
|
||||||
|
|
||||||
|
WebSocket data is rate-limited to prevent flooding:
|
||||||
|
|
||||||
|
- **Arduino data**: 20Hz max
|
||||||
|
- **GPS data**: 1Hz max
|
||||||
|
|
||||||
## Test from SSH
|
## Test from SSH
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
@@ -106,8 +140,56 @@ arduino = ArduinoService(port="/dev/ttyACM0", baudrate=115200)
|
|||||||
|
|
||||||
- **GPS**: If `gpsdclient` isn't installed or gpsd isn't running, generates fake GPS data
|
- **GPS**: If `gpsdclient` isn't installed or gpsd isn't running, generates fake GPS data
|
||||||
- **Arduino**: If `pyserial` isn't installed or serial port unavailable, generates fake telemetry
|
- **Arduino**: If `pyserial` isn't installed or serial port unavailable, generates fake telemetry
|
||||||
|
- **GPIO**: If `RPi.GPIO` isn't available, runs in mock mode (always returns default state)
|
||||||
|
|
||||||
Both services run in stub mode for UI testing without hardware.
|
All services run in stub mode for UI testing without hardware.
|
||||||
|
|
||||||
|
## GPIO Setup
|
||||||
|
|
||||||
|
The `gpio_service.py` handles physical switch inputs (e.g., theme toggle on GPIO20).
|
||||||
|
|
||||||
|
### Known Quirks
|
||||||
|
|
||||||
|
**Use apt-installed RPi.GPIO, not pip:**
|
||||||
|
```bash
|
||||||
|
sudo apt install python3-rpi.gpio
|
||||||
|
```
|
||||||
|
|
||||||
|
The pip version (`RPi.GPIO`) requires compilation with `python3-dev` headers. The apt package is pre-compiled and Just Works. The venv must be created with `--system-site-packages` to see it.
|
||||||
|
|
||||||
|
**gpiozero doesn't work (TODO):**
|
||||||
|
|
||||||
|
`gpiozero` is the "modern" GPIO library but has issues in this setup:
|
||||||
|
- Requires a pin factory backend (`lgpio`, `rpigpio`, `pigpio`, or `native`)
|
||||||
|
- `lgpio`/`rpi-lgpio` via pip needs `swig` to compile
|
||||||
|
- `native` backend breaks under gevent monkey-patching (`select.epoll` missing)
|
||||||
|
- May revisit if we need gpiozero-specific features
|
||||||
|
|
||||||
|
**Software pull-up/down conflicts with external resistors:**
|
||||||
|
|
||||||
|
If using an external pull-down resistor (especially high values like 1MΩ), disable the software pull:
|
||||||
|
```python
|
||||||
|
GPIO.setup(pin, GPIO.IN, pull_up_down=GPIO.PUD_OFF)
|
||||||
|
```
|
||||||
|
|
||||||
|
The Pi's internal pull-down (~50kΩ) will overpower high-value external resistors, causing unexpected voltage divider behavior.
|
||||||
|
|
||||||
|
**Debouncing:**
|
||||||
|
|
||||||
|
Physical switches/connectors need debouncing. Current implementation requires 15 consecutive identical readings (~750ms at 20Hz) before accepting a state change. Tune `required_consecutive` in `gpio_service.py` as needed.
|
||||||
|
|
||||||
|
## Utilities
|
||||||
|
|
||||||
|
Standalone tools live in `pi/utils/` (not part of the backend service):
|
||||||
|
|
||||||
|
| Tool | Description |
|
||||||
|
|------|-------------|
|
||||||
|
| `at_terminal.py` | Interactive AT command terminal for SIM7600 (pyserial). Default port: `/dev/ttyUSB2` |
|
||||||
|
|
||||||
|
```bash
|
||||||
|
python pi/utils/at_terminal.py # default /dev/ttyUSB2
|
||||||
|
python pi/utils/at_terminal.py /dev/ttyUSB3 # specify port
|
||||||
|
```
|
||||||
|
|
||||||
## Deploy
|
## Deploy
|
||||||
|
|
||||||
|
|||||||
141
pi/backend/gpio_service.py
Normal file
141
pi/backend/gpio_service.py
Normal file
@@ -0,0 +1,141 @@
|
|||||||
|
"""GPIO service for Pi Zero - edge-triggered monitoring.
|
||||||
|
|
||||||
|
Polls GPIO pins and exposes state changes for inclusion in other payloads.
|
||||||
|
Keeps UART separate (handled by arduino_service).
|
||||||
|
|
||||||
|
Tries RPi.GPIO first (apt install python3-rpi.gpio), falls back to gpiozero.
|
||||||
|
"""
|
||||||
|
|
||||||
|
import gevent
|
||||||
|
|
||||||
|
# Try RPi.GPIO first (commonly installed via apt on Pi)
|
||||||
|
_BACKEND = None
|
||||||
|
try:
|
||||||
|
import RPi.GPIO as GPIO
|
||||||
|
_BACKEND = "rpigpio"
|
||||||
|
print("[GPIO] Using RPi.GPIO backend")
|
||||||
|
except ImportError:
|
||||||
|
try:
|
||||||
|
from gpiozero import Button
|
||||||
|
_BACKEND = "gpiozero"
|
||||||
|
print("[GPIO] Using gpiozero backend")
|
||||||
|
except ImportError:
|
||||||
|
print("[GPIO] No GPIO library available - running in mock mode")
|
||||||
|
|
||||||
|
|
||||||
|
# Pin assignments
|
||||||
|
PIN_THEME_SWITCH = 20 # Physical switch for light/dark theme
|
||||||
|
|
||||||
|
|
||||||
|
class GPIOService:
|
||||||
|
"""Monitors GPIO pins and tracks state changes."""
|
||||||
|
|
||||||
|
def __init__(self):
|
||||||
|
self._running = False
|
||||||
|
self._greenlet = None
|
||||||
|
self._theme_button = None # gpiozero only
|
||||||
|
self._gpio_working = False
|
||||||
|
|
||||||
|
# Theme switch state
|
||||||
|
self._theme_switch_state = False # False = light, True = dark
|
||||||
|
self._pending_state = None # Candidate new state
|
||||||
|
self._pending_count = 0 # Consecutive readings of pending state
|
||||||
|
|
||||||
|
if _BACKEND == "rpigpio":
|
||||||
|
try:
|
||||||
|
GPIO.setmode(GPIO.BCM)
|
||||||
|
GPIO.setwarnings(False)
|
||||||
|
# No software pull - using external hardware pull-down
|
||||||
|
GPIO.setup(PIN_THEME_SWITCH, GPIO.IN, pull_up_down=GPIO.PUD_OFF)
|
||||||
|
self._gpio_working = True
|
||||||
|
except Exception as e:
|
||||||
|
print(f"[GPIO] RPi.GPIO init failed: {e}")
|
||||||
|
elif _BACKEND == "gpiozero":
|
||||||
|
try:
|
||||||
|
self._theme_button = Button(PIN_THEME_SWITCH, pull_up=False)
|
||||||
|
self._gpio_working = True
|
||||||
|
except Exception as e:
|
||||||
|
print(f"[GPIO] gpiozero init failed: {e}")
|
||||||
|
|
||||||
|
def _read_pin(self):
|
||||||
|
"""Read current pin state. Returns True if HIGH (dark mode)."""
|
||||||
|
if _BACKEND == "rpigpio":
|
||||||
|
return GPIO.input(PIN_THEME_SWITCH) == GPIO.HIGH
|
||||||
|
elif _BACKEND == "gpiozero" and self._theme_button:
|
||||||
|
return self._theme_button.is_pressed
|
||||||
|
return self._theme_switch_state # Mock: return current
|
||||||
|
|
||||||
|
def start(self):
|
||||||
|
"""Start background polling."""
|
||||||
|
if self._running:
|
||||||
|
return
|
||||||
|
self._running = True
|
||||||
|
|
||||||
|
# Read initial state
|
||||||
|
if self._gpio_working:
|
||||||
|
self._theme_switch_state = self._read_pin()
|
||||||
|
else:
|
||||||
|
self._theme_switch_state = True # Mock: default dark
|
||||||
|
|
||||||
|
self._greenlet = gevent.spawn(self._poll_loop)
|
||||||
|
print(f"[GPIO] Started, theme_switch initial={self._theme_switch_state}")
|
||||||
|
|
||||||
|
def stop(self):
|
||||||
|
"""Stop background polling."""
|
||||||
|
self._running = False
|
||||||
|
if self._greenlet:
|
||||||
|
self._greenlet.kill()
|
||||||
|
self._greenlet = None
|
||||||
|
if _BACKEND == "rpigpio":
|
||||||
|
try:
|
||||||
|
GPIO.cleanup([PIN_THEME_SWITCH])
|
||||||
|
except Exception:
|
||||||
|
pass
|
||||||
|
elif self._theme_button:
|
||||||
|
self._theme_button.close()
|
||||||
|
self._theme_button = None
|
||||||
|
|
||||||
|
def _poll_loop(self):
|
||||||
|
"""Poll GPIO at ~20Hz, update state with consecutive-read debounce."""
|
||||||
|
poll_count = 0
|
||||||
|
# Require N consecutive same readings to accept state change
|
||||||
|
# At 20Hz: 10 readings = 500ms, 20 readings = 1s
|
||||||
|
required_consecutive = 11 # ~550ms of stable signal
|
||||||
|
|
||||||
|
while self._running:
|
||||||
|
gevent.sleep(0.05) # 20Hz
|
||||||
|
poll_count += 1
|
||||||
|
|
||||||
|
if self._gpio_working:
|
||||||
|
current = self._read_pin()
|
||||||
|
|
||||||
|
if current != self._theme_switch_state:
|
||||||
|
# Different from accepted state - count towards change
|
||||||
|
if current == self._pending_state:
|
||||||
|
self._pending_count += 1
|
||||||
|
else:
|
||||||
|
# New candidate state
|
||||||
|
self._pending_state = current
|
||||||
|
self._pending_count = 1
|
||||||
|
|
||||||
|
# Accept change after enough consecutive readings
|
||||||
|
if self._pending_count >= required_consecutive:
|
||||||
|
self._theme_switch_state = current
|
||||||
|
self._pending_state = None
|
||||||
|
self._pending_count = 0
|
||||||
|
print(f"[GPIO] Theme switch: {current} (dark={current})")
|
||||||
|
else:
|
||||||
|
# Matches current state - reset any pending change
|
||||||
|
self._pending_state = None
|
||||||
|
self._pending_count = 0
|
||||||
|
|
||||||
|
# Heartbeat log every ~5 seconds (100 polls at 20Hz)
|
||||||
|
if poll_count >= 100:
|
||||||
|
poll_count = 0
|
||||||
|
raw = 1 if self._theme_switch_state else 0
|
||||||
|
print(f"[GPIO] Pin {PIN_THEME_SWITCH}: {raw} (dark={self._theme_switch_state})")
|
||||||
|
|
||||||
|
@property
|
||||||
|
def theme_switch(self):
|
||||||
|
"""Current theme switch state (True = dark, False = light)."""
|
||||||
|
return self._theme_switch_state
|
||||||
@@ -1,10 +1,18 @@
|
|||||||
"""GPS service - connects to gpsd, buffers data, handles reconnection."""
|
"""GPS service - connects to gpsd, buffers data, handles reconnection."""
|
||||||
|
|
||||||
|
import random
|
||||||
import threading
|
import threading
|
||||||
import time
|
import time
|
||||||
from collections import deque
|
from collections import deque
|
||||||
from typing import Any
|
from typing import Any
|
||||||
|
|
||||||
|
# ============================================================================
|
||||||
|
# DEBUG MODE - Set True for development without GPS hardware
|
||||||
|
# When True: skips gpsd entirely, generates realistic mock data
|
||||||
|
# When False: connects to real gpsd (requires GPS device)
|
||||||
|
# ============================================================================
|
||||||
|
_GPS_DEBUG = False
|
||||||
|
|
||||||
# gpsdclient is a modern, simple gpsd client
|
# gpsdclient is a modern, simple gpsd client
|
||||||
# Install gpsd on Pi: sudo apt install gpsd gpsd-clients
|
# Install gpsd on Pi: sudo apt install gpsd gpsd-clients
|
||||||
# Configure: sudo nano /etc/default/gpsd (set DEVICES="/dev/ttyUSB0" or similar)
|
# Configure: sudo nano /etc/default/gpsd (set DEVICES="/dev/ttyUSB0" or similar)
|
||||||
@@ -32,6 +40,14 @@ class GPSService:
|
|||||||
# Callback for push-based updates
|
# Callback for push-based updates
|
||||||
self._on_data_callback = None
|
self._on_data_callback = None
|
||||||
|
|
||||||
|
# GPS state tracking (NMEA can't distinguish "acquiring" from "lost")
|
||||||
|
self._has_ever_fixed = False # True after first valid fix this session
|
||||||
|
|
||||||
|
# Periodic status logging
|
||||||
|
self._last_status_log = 0.0
|
||||||
|
self._last_state_emit = 0.0
|
||||||
|
self._fix_count = 0
|
||||||
|
|
||||||
def set_on_data(self, callback):
|
def set_on_data(self, callback):
|
||||||
"""Set callback for new GPS fix. Called with fix dict."""
|
"""Set callback for new GPS fix. Called with fix dict."""
|
||||||
self._on_data_callback = callback
|
self._on_data_callback = callback
|
||||||
@@ -45,6 +61,17 @@ class GPSService:
|
|||||||
with self._lock:
|
with self._lock:
|
||||||
return self._latest.copy() if self._latest else {"error": "no data"}
|
return self._latest.copy() if self._latest else {"error": "no data"}
|
||||||
|
|
||||||
|
def _gps_state(self, fix: dict) -> str:
|
||||||
|
"""Determine GPS state: acquiring, fix, or lost.
|
||||||
|
|
||||||
|
NMEA doesn't distinguish 'never had fix' from 'lost signal' — both
|
||||||
|
report mode 1 with no position. We track it ourselves.
|
||||||
|
"""
|
||||||
|
has_fix = fix.get("mode") in (2, 3) and fix.get("lat") is not None
|
||||||
|
if has_fix:
|
||||||
|
return "fix"
|
||||||
|
return "lost" if self._has_ever_fixed else "acquiring"
|
||||||
|
|
||||||
def get_buffer(self) -> list[dict[str, Any]]:
|
def get_buffer(self) -> list[dict[str, Any]]:
|
||||||
"""Get buffered GPS history."""
|
"""Get buffered GPS history."""
|
||||||
with self._lock:
|
with self._lock:
|
||||||
@@ -57,6 +84,7 @@ class GPSService:
|
|||||||
self._running = True
|
self._running = True
|
||||||
self._thread = threading.Thread(target=self._reader_loop, daemon=True)
|
self._thread = threading.Thread(target=self._reader_loop, daemon=True)
|
||||||
self._thread.start()
|
self._thread.start()
|
||||||
|
print("[GPS] Service started")
|
||||||
|
|
||||||
def stop(self):
|
def stop(self):
|
||||||
"""Stop background reader."""
|
"""Stop background reader."""
|
||||||
@@ -66,6 +94,7 @@ class GPSService:
|
|||||||
|
|
||||||
def _reader_loop(self):
|
def _reader_loop(self):
|
||||||
"""Main reader loop with reconnection logic."""
|
"""Main reader loop with reconnection logic."""
|
||||||
|
print("[GPS] Reader thread running")
|
||||||
while self._running:
|
while self._running:
|
||||||
try:
|
try:
|
||||||
self._connect_and_read()
|
self._connect_and_read()
|
||||||
@@ -76,23 +105,41 @@ class GPSService:
|
|||||||
|
|
||||||
def _connect_and_read(self):
|
def _connect_and_read(self):
|
||||||
"""Connect to gpsd and read data."""
|
"""Connect to gpsd and read data."""
|
||||||
|
# Debug mode: skip gpsd entirely, use stub data
|
||||||
|
if _GPS_DEBUG:
|
||||||
|
print("[GPS] Debug mode enabled, using stub data")
|
||||||
|
self._stub_mode()
|
||||||
|
return
|
||||||
|
|
||||||
if GPSDClient is None:
|
if GPSDClient is None:
|
||||||
# Stub mode - no gpsd client installed
|
|
||||||
print("[GPS] gpsdclient not installed, running in stub mode")
|
print("[GPS] gpsdclient not installed, running in stub mode")
|
||||||
self._stub_mode()
|
self._stub_mode()
|
||||||
return
|
return
|
||||||
|
|
||||||
|
# Quick check if gpsd is reachable before attempting connection
|
||||||
|
import socket
|
||||||
|
try:
|
||||||
|
sock = socket.create_connection((self.host, self.port), timeout=2.0)
|
||||||
|
sock.close()
|
||||||
|
except (socket.timeout, socket.error, OSError) as e:
|
||||||
|
print(f"[GPS] gpsd not reachable at {self.host}:{self.port}: {e}")
|
||||||
|
raise ConnectionError(f"gpsd not reachable: {e}")
|
||||||
|
|
||||||
try:
|
try:
|
||||||
client = GPSDClient(host=self.host, port=self.port)
|
client = GPSDClient(host=self.host, port=self.port)
|
||||||
except Exception as e:
|
except Exception as e:
|
||||||
print(f"[GPS] Cannot connect to gpsd at {self.host}:{self.port}: {e}, falling back to stub mode")
|
print(f"[GPS] Cannot connect to gpsd at {self.host}:{self.port}: {e}")
|
||||||
self._stub_mode()
|
raise ConnectionError(f"gpsd connection failed: {e}")
|
||||||
return
|
|
||||||
|
|
||||||
with client:
|
with client:
|
||||||
self._connected = True
|
self._connected = True
|
||||||
print(f"[GPS] Connected to gpsd at {self.host}:{self.port}")
|
print(f"[GPS] Connected to gpsd at {self.host}:{self.port}")
|
||||||
|
|
||||||
|
self._last_status_log = time.time()
|
||||||
|
self._fix_count = 0
|
||||||
|
# 120s for initial cold fix, 10s for signal loss after first fix
|
||||||
|
fix_timeout = time.time() + 120.0
|
||||||
|
|
||||||
for result in client.dict_stream(filter=["TPV"]):
|
for result in client.dict_stream(filter=["TPV"]):
|
||||||
if not self._running:
|
if not self._running:
|
||||||
break
|
break
|
||||||
@@ -106,8 +153,36 @@ class GPSService:
|
|||||||
"speed": result.get("speed"), # m/s
|
"speed": result.get("speed"), # m/s
|
||||||
"track": result.get("track"), # heading in degrees
|
"track": result.get("track"), # heading in degrees
|
||||||
"mode": result.get("mode"), # 0=no fix, 2=2D, 3=3D
|
"mode": result.get("mode"), # 0=no fix, 2=2D, 3=3D
|
||||||
|
"satellites": result.get("satellites"), # from SKY messages
|
||||||
}
|
}
|
||||||
|
|
||||||
|
# Compute state and attach to fix
|
||||||
|
fix["gps_state"] = self._gps_state(fix)
|
||||||
|
|
||||||
|
# Check if this is a real fix (has position) or just empty TPV
|
||||||
|
if fix.get("lat") is None and fix.get("mode") in (None, 0, 1):
|
||||||
|
# No real data yet, check timeout
|
||||||
|
if time.time() > fix_timeout:
|
||||||
|
timeout_s = "120s" if not self._has_ever_fixed else "10s"
|
||||||
|
print(f"[GPS] No GPS fix after {timeout_s}, will retry connection")
|
||||||
|
raise ConnectionError("No GPS fix within timeout")
|
||||||
|
# Emit state periodically so UI knows we're alive
|
||||||
|
now = time.time()
|
||||||
|
if now - self._last_state_emit >= 5.0:
|
||||||
|
self._last_state_emit = now
|
||||||
|
with self._lock:
|
||||||
|
self._latest = fix
|
||||||
|
if self._on_data_callback:
|
||||||
|
self._on_data_callback(fix)
|
||||||
|
continue # Skip empty fixes
|
||||||
|
|
||||||
|
# Got real data — mark first fix, reset timeout to shorter window
|
||||||
|
if not self._has_ever_fixed:
|
||||||
|
self._has_ever_fixed = True
|
||||||
|
self._last_state_emit = 0.0 # Force immediate emit on transition
|
||||||
|
print("[GPS] First fix acquired")
|
||||||
|
fix_timeout = time.time() + 10.0 # 10s timeout for signal loss
|
||||||
|
|
||||||
with self._lock:
|
with self._lock:
|
||||||
self._latest = fix
|
self._latest = fix
|
||||||
if fix.get("lat") is not None:
|
if fix.get("lat") is not None:
|
||||||
@@ -117,27 +192,124 @@ class GPSService:
|
|||||||
if self._on_data_callback:
|
if self._on_data_callback:
|
||||||
self._on_data_callback(fix)
|
self._on_data_callback(fix)
|
||||||
|
|
||||||
|
# Periodic status log (every 5s)
|
||||||
|
self._fix_count += 1
|
||||||
|
now = time.time()
|
||||||
|
if now - self._last_status_log >= 5.0:
|
||||||
|
elapsed = now - self._last_status_log
|
||||||
|
fps = self._fix_count / elapsed
|
||||||
|
speed = fix.get('speed', 0) or 0
|
||||||
|
track = fix.get('track', 0) or 0
|
||||||
|
mode = fix.get('mode', 0) or 0
|
||||||
|
sats = fix.get('satellites', '?')
|
||||||
|
print(f"[GPS] {fps:.1f} fix/s | {speed:.1f}m/s hdg={track:.0f}° mode={mode} sats={sats}")
|
||||||
|
self._last_status_log = now
|
||||||
|
self._fix_count = 0
|
||||||
|
|
||||||
def _stub_mode(self):
|
def _stub_mode(self):
|
||||||
"""Fake data for testing without gpsd."""
|
"""Generate realistic mock GPS data for development/testing.
|
||||||
import random
|
|
||||||
|
Simulates:
|
||||||
|
- Initial acquisition delay (~3s before first fix)
|
||||||
|
- Normal 3D fix with satellites
|
||||||
|
- Occasional signal loss (~30% chance per second, lasts ~2s)
|
||||||
|
- Wandering position near Tokyo
|
||||||
|
"""
|
||||||
|
self._last_status_log = time.time()
|
||||||
|
self._fix_count = 0
|
||||||
|
|
||||||
|
# Signal loss state
|
||||||
|
signal_lost = False
|
||||||
|
signal_lost_until = 0.0
|
||||||
|
|
||||||
|
# Simulate cold start acquisition (~30s)
|
||||||
|
acquiring_until = time.time() + 30.0
|
||||||
|
|
||||||
|
# Base position (Tokyo area)
|
||||||
|
base_lat = 35.6762
|
||||||
|
base_lon = 139.6503
|
||||||
|
base_alt = 40.0
|
||||||
|
|
||||||
|
# Smoothly varying heading/speed
|
||||||
|
heading = random.uniform(0, 360)
|
||||||
|
speed = random.uniform(5, 15)
|
||||||
|
|
||||||
while self._running:
|
while self._running:
|
||||||
self._connected = True
|
self._connected = True
|
||||||
fix = {
|
now = time.time()
|
||||||
"time": time.strftime("%Y-%m-%dT%H:%M:%SZ", time.gmtime()),
|
|
||||||
"lat": 35.6762 + random.uniform(-0.001, 0.001),
|
# Simulate initial acquisition period
|
||||||
"lon": 139.6503 + random.uniform(-0.001, 0.001),
|
if now < acquiring_until:
|
||||||
"alt": 40.0 + random.uniform(-5, 5),
|
signal_lost = True # No fix yet
|
||||||
"speed": random.uniform(0, 30),
|
elif signal_lost and now >= signal_lost_until:
|
||||||
"track": random.uniform(0, 360),
|
signal_lost = False
|
||||||
"mode": 3,
|
if self._has_ever_fixed:
|
||||||
}
|
print("[GPS] Signal recovered (stub)")
|
||||||
|
else:
|
||||||
|
print("[GPS] First fix acquired (stub)")
|
||||||
|
elif not signal_lost:
|
||||||
|
# ~30% chance per second to lose signal
|
||||||
|
if random.random() < 0.3:
|
||||||
|
signal_lost = True
|
||||||
|
signal_lost_until = now + 2 # fixed 2s loss
|
||||||
|
print("[GPS] Signal loss simulation (stub)")
|
||||||
|
|
||||||
|
if signal_lost:
|
||||||
|
# No fix - mode 1, no satellites, no track
|
||||||
|
# Note: use None, not float('nan') - NaN doesn't serialize to valid JSON
|
||||||
|
fix = {
|
||||||
|
"time": time.strftime("%Y-%m-%dT%H:%M:%SZ", time.gmtime()),
|
||||||
|
"lat": None,
|
||||||
|
"lon": None,
|
||||||
|
"alt": None,
|
||||||
|
"speed": None,
|
||||||
|
"track": None,
|
||||||
|
"mode": 1,
|
||||||
|
"satellites": 0,
|
||||||
|
}
|
||||||
|
else:
|
||||||
|
# Smoothly vary heading and speed
|
||||||
|
heading = (heading + random.uniform(1, 3)) % 360
|
||||||
|
speed = max(0, min(30, speed + random.uniform(-2, 2)))
|
||||||
|
|
||||||
|
if not self._has_ever_fixed:
|
||||||
|
self._has_ever_fixed = True
|
||||||
|
|
||||||
|
fix = {
|
||||||
|
"time": time.strftime("%Y-%m-%dT%H:%M:%SZ", time.gmtime()),
|
||||||
|
"lat": base_lat + random.uniform(-0.001, 0.001),
|
||||||
|
"lon": base_lon + random.uniform(-0.001, 0.001),
|
||||||
|
"alt": base_alt + random.uniform(-5, 5),
|
||||||
|
"speed": speed,
|
||||||
|
"track": heading,
|
||||||
|
"mode": 3,
|
||||||
|
"satellites": random.randint(6, 12),
|
||||||
|
}
|
||||||
|
|
||||||
|
# Attach state — same logic as real GPS path
|
||||||
|
fix["gps_state"] = self._gps_state(fix)
|
||||||
|
|
||||||
with self._lock:
|
with self._lock:
|
||||||
self._latest = fix
|
self._latest = fix
|
||||||
self._buffer.append(fix)
|
if fix.get("lat") is not None:
|
||||||
|
self._buffer.append(fix)
|
||||||
|
|
||||||
# Invoke callback with new fix
|
# Invoke callback with new fix
|
||||||
if self._on_data_callback:
|
if self._on_data_callback:
|
||||||
self._on_data_callback(fix)
|
self._on_data_callback(fix)
|
||||||
|
|
||||||
|
# Periodic status log (every 5s)
|
||||||
|
self._fix_count += 1
|
||||||
|
if now - self._last_status_log >= 5.0:
|
||||||
|
elapsed = now - self._last_status_log
|
||||||
|
fps = self._fix_count / elapsed
|
||||||
|
speed_val = fix.get('speed') or 0
|
||||||
|
track_val = fix.get('track')
|
||||||
|
track_str = f"{track_val:.0f}" if track_val is not None else "---"
|
||||||
|
mode = fix.get('mode', 0)
|
||||||
|
sats = fix.get('satellites', 0)
|
||||||
|
print(f"[GPS] {fps:.1f} fix/s | {speed_val:.1f}m/s hdg={track_str} mode={mode} sats={sats} (stub)")
|
||||||
|
self._last_status_log = now
|
||||||
|
self._fix_count = 0
|
||||||
|
|
||||||
time.sleep(1)
|
time.sleep(1)
|
||||||
|
|||||||
178
pi/backend/lte_service.py
Normal file
178
pi/backend/lte_service.py
Normal file
@@ -0,0 +1,178 @@
|
|||||||
|
"""LTE service - polls ModemManager for signal quality and connection state."""
|
||||||
|
|
||||||
|
import random
|
||||||
|
import subprocess
|
||||||
|
import re
|
||||||
|
import threading
|
||||||
|
import time
|
||||||
|
from typing import Any
|
||||||
|
|
||||||
|
# ============================================================================
|
||||||
|
# DEBUG MODE - Set True for development without modem hardware
|
||||||
|
# When True: skips mmcli entirely, generates mock LTE data
|
||||||
|
# When False: polls real ModemManager via mmcli
|
||||||
|
# ============================================================================
|
||||||
|
_LTE_DEBUG = True
|
||||||
|
|
||||||
|
|
||||||
|
class LteService:
|
||||||
|
"""Threaded LTE modem status poller.
|
||||||
|
|
||||||
|
Polls `mmcli -m 0` every 5 seconds, parses signal quality, connection
|
||||||
|
state, operator, and access technology. Emits dict via callback.
|
||||||
|
|
||||||
|
No history buffer — historical signal strength isn't useful.
|
||||||
|
"""
|
||||||
|
|
||||||
|
def __init__(self, poll_interval: float = 5.0):
|
||||||
|
self.poll_interval = poll_interval
|
||||||
|
|
||||||
|
self._latest: dict[str, Any] = {}
|
||||||
|
self._connected = False # True when mmcli responds (modem alive)
|
||||||
|
self._running = False
|
||||||
|
self._thread: threading.Thread | None = None
|
||||||
|
self._lock = threading.Lock()
|
||||||
|
|
||||||
|
# Callback for push-based updates
|
||||||
|
self._on_data_callback = None
|
||||||
|
|
||||||
|
def set_on_data(self, callback):
|
||||||
|
"""Set callback for new LTE data. Called with data dict."""
|
||||||
|
self._on_data_callback = callback
|
||||||
|
|
||||||
|
@property
|
||||||
|
def connected(self) -> bool:
|
||||||
|
"""Whether the modem is reachable via mmcli."""
|
||||||
|
return self._connected
|
||||||
|
|
||||||
|
def get_latest(self) -> dict[str, Any]:
|
||||||
|
"""Get most recent LTE status."""
|
||||||
|
with self._lock:
|
||||||
|
return self._latest.copy() if self._latest else {"error": "no data"}
|
||||||
|
|
||||||
|
def start(self):
|
||||||
|
"""Start background LTE poller thread."""
|
||||||
|
if self._running:
|
||||||
|
return
|
||||||
|
self._running = True
|
||||||
|
self._thread = threading.Thread(target=self._poll_loop, daemon=True)
|
||||||
|
self._thread.start()
|
||||||
|
print("[LTE] Service started")
|
||||||
|
|
||||||
|
def stop(self):
|
||||||
|
"""Stop background poller."""
|
||||||
|
self._running = False
|
||||||
|
if self._thread:
|
||||||
|
self._thread.join(timeout=2.0)
|
||||||
|
|
||||||
|
def _poll_loop(self):
|
||||||
|
"""Main poll loop."""
|
||||||
|
print("[LTE] Poller thread running")
|
||||||
|
while self._running:
|
||||||
|
try:
|
||||||
|
if _LTE_DEBUG:
|
||||||
|
data = self._stub_poll()
|
||||||
|
else:
|
||||||
|
data = self._real_poll()
|
||||||
|
|
||||||
|
with self._lock:
|
||||||
|
self._latest = data
|
||||||
|
|
||||||
|
if self._on_data_callback:
|
||||||
|
self._on_data_callback(data)
|
||||||
|
|
||||||
|
except Exception as e:
|
||||||
|
print(f"[LTE] Poll error: {e}")
|
||||||
|
self._connected = False
|
||||||
|
|
||||||
|
time.sleep(self.poll_interval)
|
||||||
|
|
||||||
|
def _real_poll(self) -> dict[str, Any]:
|
||||||
|
"""Poll mmcli -m 0 and parse output."""
|
||||||
|
try:
|
||||||
|
result = subprocess.run(
|
||||||
|
["mmcli", "-m", "0"],
|
||||||
|
capture_output=True,
|
||||||
|
text=True,
|
||||||
|
timeout=5.0,
|
||||||
|
)
|
||||||
|
|
||||||
|
if result.returncode != 0:
|
||||||
|
self._connected = False
|
||||||
|
return {
|
||||||
|
"connected": False,
|
||||||
|
"signal": 0,
|
||||||
|
"operator": None,
|
||||||
|
"access_tech": None,
|
||||||
|
}
|
||||||
|
|
||||||
|
output = result.stdout
|
||||||
|
self._connected = True
|
||||||
|
|
||||||
|
# Parse signal quality: "signal quality: 68 (recent)"
|
||||||
|
signal = 0
|
||||||
|
m = re.search(r"signal quality:\s*(\d+)", output)
|
||||||
|
if m:
|
||||||
|
signal = int(m.group(1))
|
||||||
|
|
||||||
|
# Parse state: "state: connected" / "registered" / "searching" etc.
|
||||||
|
state = None
|
||||||
|
m = re.search(r"^\s*state:\s*(\S+)", output, re.MULTILINE)
|
||||||
|
if m:
|
||||||
|
state = m.group(1).strip("'\"")
|
||||||
|
|
||||||
|
# Parse operator: "operator name: KDDI KDDI"
|
||||||
|
operator = None
|
||||||
|
m = re.search(r"operator name:\s*(.+)", output)
|
||||||
|
if m:
|
||||||
|
operator = m.group(1).strip()
|
||||||
|
|
||||||
|
# Parse access tech: "access tech: lte"
|
||||||
|
access_tech = None
|
||||||
|
m = re.search(r"access tech:\s*(\S+)", output)
|
||||||
|
if m:
|
||||||
|
access_tech = m.group(1).strip("'\"")
|
||||||
|
|
||||||
|
network_connected = state in ("connected", "registered")
|
||||||
|
|
||||||
|
return {
|
||||||
|
"connected": network_connected,
|
||||||
|
"signal": signal,
|
||||||
|
"operator": operator,
|
||||||
|
"access_tech": access_tech,
|
||||||
|
}
|
||||||
|
|
||||||
|
except subprocess.TimeoutExpired:
|
||||||
|
print("[LTE] mmcli timed out")
|
||||||
|
self._connected = False
|
||||||
|
return {
|
||||||
|
"connected": False,
|
||||||
|
"signal": 0,
|
||||||
|
"operator": None,
|
||||||
|
"access_tech": None,
|
||||||
|
}
|
||||||
|
except FileNotFoundError:
|
||||||
|
print("[LTE] mmcli not found, falling back to stub mode")
|
||||||
|
self._connected = False
|
||||||
|
return self._stub_poll()
|
||||||
|
|
||||||
|
# Stub state lives across polls
|
||||||
|
_stub_signal: float = 70.0
|
||||||
|
|
||||||
|
def _stub_poll(self) -> dict[str, Any]:
|
||||||
|
"""Generate mock LTE data for development.
|
||||||
|
|
||||||
|
Simulates connected state with signal wandering 60-80.
|
||||||
|
"""
|
||||||
|
self._connected = True
|
||||||
|
|
||||||
|
# Random walk signal, clamped to 60-80
|
||||||
|
self._stub_signal += random.uniform(-3, 3)
|
||||||
|
self._stub_signal = max(60, min(80, self._stub_signal))
|
||||||
|
|
||||||
|
return {
|
||||||
|
"connected": True,
|
||||||
|
"signal": int(self._stub_signal),
|
||||||
|
"operator": "STUB",
|
||||||
|
"access_tech": "lte",
|
||||||
|
}
|
||||||
@@ -8,6 +8,8 @@ from flask_socketio import SocketIO, emit
|
|||||||
|
|
||||||
from gps_service import GPSService
|
from gps_service import GPSService
|
||||||
from arduino_service import ArduinoService
|
from arduino_service import ArduinoService
|
||||||
|
from gpio_service import GPIOService
|
||||||
|
from lte_service import LteService
|
||||||
from throttle import Throttle
|
from throttle import Throttle
|
||||||
|
|
||||||
app = Flask(__name__)
|
app = Flask(__name__)
|
||||||
@@ -19,10 +21,13 @@ socketio = SocketIO(app, async_mode="gevent", cors_allowed_origins="*")
|
|||||||
# Services
|
# Services
|
||||||
gps = GPSService()
|
gps = GPSService()
|
||||||
arduino = ArduinoService()
|
arduino = ArduinoService()
|
||||||
|
gpio = GPIOService()
|
||||||
|
lte = LteService()
|
||||||
|
|
||||||
# Throttles for emission rate limiting (20Hz for arduino, 1Hz for GPS)
|
# Throttles for emission rate limiting (20Hz for arduino, 1Hz for GPS, 5s for LTE)
|
||||||
arduino_throttle = Throttle(min_interval=0.05) # 20Hz max
|
arduino_throttle = Throttle(min_interval=0.05) # 20Hz max
|
||||||
gps_throttle = Throttle(min_interval=1.0) # 1Hz max
|
gps_throttle = Throttle(min_interval=1.0) # 1Hz max
|
||||||
|
lte_throttle = Throttle(min_interval=5.0) # Every 5s — signal doesn't need real-time
|
||||||
|
|
||||||
# Track connected clients
|
# Track connected clients
|
||||||
connected_clients = set()
|
connected_clients = set()
|
||||||
@@ -43,6 +48,7 @@ def handle_connect():
|
|||||||
emit("status", {
|
emit("status", {
|
||||||
"gps_connected": gps.connected,
|
"gps_connected": gps.connected,
|
||||||
"arduino_connected": arduino.connected,
|
"arduino_connected": arduino.connected,
|
||||||
|
"theme_switch": gpio.theme_switch,
|
||||||
})
|
})
|
||||||
|
|
||||||
# Send latest data if available
|
# Send latest data if available
|
||||||
@@ -54,6 +60,10 @@ def handle_connect():
|
|||||||
if "error" not in gps_data:
|
if "error" not in gps_data:
|
||||||
emit("gps", gps_data)
|
emit("gps", gps_data)
|
||||||
|
|
||||||
|
lte_data = lte.get_latest()
|
||||||
|
if "error" not in lte_data:
|
||||||
|
emit("lte", lte_data)
|
||||||
|
|
||||||
|
|
||||||
@socketio.on("disconnect")
|
@socketio.on("disconnect")
|
||||||
def handle_disconnect():
|
def handle_disconnect():
|
||||||
@@ -126,6 +136,14 @@ def handle_emergency(data):
|
|||||||
|
|
||||||
def on_arduino_data(data):
|
def on_arduino_data(data):
|
||||||
"""Called by ArduinoService when new telemetry arrives."""
|
"""Called by ArduinoService when new telemetry arrives."""
|
||||||
|
# Always include current GPIO state (UI dedupes)
|
||||||
|
data = dict(data) # Don't mutate original
|
||||||
|
data["theme_switch"] = gpio.theme_switch
|
||||||
|
|
||||||
|
# backend voltage offset correction
|
||||||
|
if "voltage" in data:
|
||||||
|
data["voltage"] += 0.2 # Calibration offset
|
||||||
|
|
||||||
def emit_fn(d):
|
def emit_fn(d):
|
||||||
socketio.emit("arduino", d)
|
socketio.emit("arduino", d)
|
||||||
|
|
||||||
@@ -140,6 +158,14 @@ def on_gps_data(data):
|
|||||||
gps_throttle.maybe_emit(data, emit_fn)
|
gps_throttle.maybe_emit(data, emit_fn)
|
||||||
|
|
||||||
|
|
||||||
|
def on_lte_data(data):
|
||||||
|
"""Called by LteService when new status polled."""
|
||||||
|
def emit_fn(d):
|
||||||
|
socketio.emit("lte", d)
|
||||||
|
|
||||||
|
lte_throttle.maybe_emit(data, emit_fn)
|
||||||
|
|
||||||
|
|
||||||
def on_arduino_ack(cmd, status, extra):
|
def on_arduino_ack(cmd, status, extra):
|
||||||
"""Called by ArduinoService when ACK received from Arduino."""
|
"""Called by ArduinoService when ACK received from Arduino."""
|
||||||
socketio.emit("ack", {
|
socketio.emit("ack", {
|
||||||
@@ -165,6 +191,9 @@ def throttle_flusher():
|
|||||||
if gps_throttle.has_pending:
|
if gps_throttle.has_pending:
|
||||||
gps_throttle.flush(lambda d: socketio.emit("gps", d))
|
gps_throttle.flush(lambda d: socketio.emit("gps", d))
|
||||||
|
|
||||||
|
if lte_throttle.has_pending:
|
||||||
|
lte_throttle.flush(lambda d: socketio.emit("lte", d))
|
||||||
|
|
||||||
|
|
||||||
# -----------------------------------------------------------------------------
|
# -----------------------------------------------------------------------------
|
||||||
# REST API (backward compatibility)
|
# REST API (backward compatibility)
|
||||||
@@ -173,10 +202,15 @@ def throttle_flusher():
|
|||||||
@app.route("/health")
|
@app.route("/health")
|
||||||
def health():
|
def health():
|
||||||
"""Health check endpoint."""
|
"""Health check endpoint."""
|
||||||
|
gps_latest = gps.get_latest()
|
||||||
|
lte_latest = lte.get_latest()
|
||||||
return jsonify({
|
return jsonify({
|
||||||
"status": "ok",
|
"status": "ok",
|
||||||
"gps_connected": gps.connected,
|
"gps_connected": gps.connected,
|
||||||
|
"gps_state": gps_latest.get("gps_state", "acquiring"),
|
||||||
"arduino_connected": arduino.connected,
|
"arduino_connected": arduino.connected,
|
||||||
|
"lte_connected": lte.connected,
|
||||||
|
"lte_signal": lte_latest.get("signal"),
|
||||||
"ws_clients": len(connected_clients),
|
"ws_clients": len(connected_clients),
|
||||||
})
|
})
|
||||||
|
|
||||||
@@ -193,6 +227,12 @@ def gps_history():
|
|||||||
return jsonify(gps.get_buffer())
|
return jsonify(gps.get_buffer())
|
||||||
|
|
||||||
|
|
||||||
|
@app.route("/lte")
|
||||||
|
def lte_data():
|
||||||
|
"""Current LTE modem status."""
|
||||||
|
return jsonify(lte.get_latest())
|
||||||
|
|
||||||
|
|
||||||
@app.route("/arduino")
|
@app.route("/arduino")
|
||||||
def arduino_data():
|
def arduino_data():
|
||||||
"""Current Arduino telemetry (voltage, rpm, etc)."""
|
"""Current Arduino telemetry (voltage, rpm, etc)."""
|
||||||
@@ -215,10 +255,13 @@ def main():
|
|||||||
arduino.set_on_data(on_arduino_data)
|
arduino.set_on_data(on_arduino_data)
|
||||||
arduino.set_on_ack(on_arduino_ack)
|
arduino.set_on_ack(on_arduino_ack)
|
||||||
gps.set_on_data(on_gps_data)
|
gps.set_on_data(on_gps_data)
|
||||||
|
lte.set_on_data(on_lte_data)
|
||||||
|
|
||||||
# Start services
|
# Start services
|
||||||
gps.start()
|
gps.start()
|
||||||
arduino.start()
|
arduino.start()
|
||||||
|
gpio.start()
|
||||||
|
lte.start()
|
||||||
|
|
||||||
# Start throttle flusher in background
|
# Start throttle flusher in background
|
||||||
socketio.start_background_task(throttle_flusher)
|
socketio.start_background_task(throttle_flusher)
|
||||||
@@ -230,6 +273,8 @@ def main():
|
|||||||
finally:
|
finally:
|
||||||
arduino.stop()
|
arduino.stop()
|
||||||
gps.stop()
|
gps.stop()
|
||||||
|
gpio.stop()
|
||||||
|
lte.stop()
|
||||||
|
|
||||||
|
|
||||||
if __name__ == "__main__":
|
if __name__ == "__main__":
|
||||||
|
|||||||
@@ -10,6 +10,8 @@ dependencies = [
|
|||||||
"gevent-websocket>=0.10",
|
"gevent-websocket>=0.10",
|
||||||
"gpsdclient>=1.3",
|
"gpsdclient>=1.3",
|
||||||
"pyserial>=3.5",
|
"pyserial>=3.5",
|
||||||
|
# GPIO: install via apt (sudo apt install python3-rpi.gpio)
|
||||||
|
# Not listed here because pip versions require compilation
|
||||||
]
|
]
|
||||||
|
|
||||||
[project.optional-dependencies]
|
[project.optional-dependencies]
|
||||||
|
|||||||
49
pi/backend/utils/at_terminal.py
Normal file
49
pi/backend/utils/at_terminal.py
Normal file
@@ -0,0 +1,49 @@
|
|||||||
|
"""Quick AT command terminal - minicom but less hostile.
|
||||||
|
|
||||||
|
Usage:
|
||||||
|
python at_terminal.py [port]
|
||||||
|
|
||||||
|
Default port: /dev/ttyUSB2 (SIM7600 AT command interface)
|
||||||
|
"""
|
||||||
|
|
||||||
|
import sys
|
||||||
|
import serial
|
||||||
|
import threading
|
||||||
|
|
||||||
|
PORT = sys.argv[1] if len(sys.argv) > 1 else "/dev/ttyUSB2"
|
||||||
|
BAUD = 115200
|
||||||
|
|
||||||
|
|
||||||
|
def reader(ser):
|
||||||
|
"""Background thread: print everything the modem sends."""
|
||||||
|
while True:
|
||||||
|
try:
|
||||||
|
data = ser.read(ser.in_waiting or 1)
|
||||||
|
if data:
|
||||||
|
sys.stdout.write(data.decode("utf-8", errors="replace"))
|
||||||
|
sys.stdout.flush()
|
||||||
|
except Exception:
|
||||||
|
break
|
||||||
|
|
||||||
|
|
||||||
|
def main():
|
||||||
|
print(f"Opening {PORT} @ {BAUD} baud")
|
||||||
|
print("Type AT commands. Ctrl+C to quit.\n")
|
||||||
|
|
||||||
|
ser = serial.Serial(PORT, BAUD, timeout=0.1)
|
||||||
|
|
||||||
|
t = threading.Thread(target=reader, args=(ser,), daemon=True)
|
||||||
|
t.start()
|
||||||
|
|
||||||
|
try:
|
||||||
|
while True:
|
||||||
|
line = input()
|
||||||
|
ser.write((line + "\r\n").encode())
|
||||||
|
except (KeyboardInterrupt, EOFError):
|
||||||
|
print("\nBye.")
|
||||||
|
finally:
|
||||||
|
ser.close()
|
||||||
|
|
||||||
|
|
||||||
|
if __name__ == "__main__":
|
||||||
|
main()
|
||||||
@@ -22,11 +22,30 @@ All services use singleton pattern with `ServiceName.instance`.
|
|||||||
| Service | Role |
|
| Service | Role |
|
||||||
|---------|------|
|
|---------|------|
|
||||||
| `ConfigService` | Loads `config.json`, exposes settings |
|
| `ConfigService` | Loads `config.json`, exposes settings |
|
||||||
| `PiIO` | Pi hardware interface (CPU temp, future GPIO) |
|
| `WebSocketService` | socket.io client, streams for arduino/gps/connection/debug, auto-reconnect |
|
||||||
|
| `PiIO` | Pi hardware interface (CPU temp) |
|
||||||
| `OverheatMonitor` | Polls temp, fires callback when threshold exceeded |
|
| `OverheatMonitor` | Polls temp, fires callback when threshold exceeded |
|
||||||
| `ThemeService` | Dark/bright mode state, notifies listeners |
|
| `ThemeService` | Dark/bright mode state, notifies listeners |
|
||||||
| `TestFlipFlopService` | Debug: toggles theme + navigator emotion every 2s |
|
| `TestFlipFlopService` | Debug: toggles theme + navigator emotion every 2s |
|
||||||
|
|
||||||
|
## Key Widgets
|
||||||
|
|
||||||
|
| Widget | Purpose |
|
||||||
|
|--------|---------|
|
||||||
|
| `NavigatorWidget` | Animated character with emotion states (images precached at startup) |
|
||||||
|
| `AccelGraph` | Real-time accelerometer visualization with gravity compensation |
|
||||||
|
| `GpsCompass` | GPS heading compass with rotating navigation icon and degree readout |
|
||||||
|
| `WhiskeyMark` | Gimbal-style horizon indicator using IMU roll/pitch |
|
||||||
|
| `SystemBar` | Top status bar (time, connection, Pi temp) |
|
||||||
|
| `StatBox` | Reusable metric display box |
|
||||||
|
| `DebugConsole` | Scrolling log overlay for diagnostics |
|
||||||
|
|
||||||
|
## Notes
|
||||||
|
|
||||||
|
- **Gravity compensation**: Accelerometer display subtracts 1g from Z-axis to show deviation from vertical
|
||||||
|
- **Navigator precaching**: All navigator images are loaded during splash screen to prevent frame drops
|
||||||
|
- **Theme switching**: Backend sends `theme_switch` via WebSocket status events (triggered by GPIO)
|
||||||
|
|
||||||
## Theme System
|
## Theme System
|
||||||
|
|
||||||
- `AppColors` — static color constants (dark/bright variants), auto-generated from JSON
|
- `AppColors` — static color constants (dark/bright variants), auto-generated from JSON
|
||||||
|
|||||||
@@ -19,7 +19,7 @@ class AppRoot extends StatefulWidget {
|
|||||||
class _AppRootState extends State<AppRoot> {
|
class _AppRootState extends State<AppRoot> {
|
||||||
bool _initialized = false;
|
bool _initialized = false;
|
||||||
bool _overheatTriggered = false;
|
bool _overheatTriggered = false;
|
||||||
String _initStatus = 'Starting...';
|
final Map<String, String> _initStatuses = {};
|
||||||
|
|
||||||
@override
|
@override
|
||||||
void initState() {
|
void initState() {
|
||||||
@@ -33,24 +33,35 @@ class _AppRootState extends State<AppRoot> {
|
|||||||
super.dispose();
|
super.dispose();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void _updateStatus(String key, String value) {
|
||||||
|
setState(() => _initStatuses[key] = value);
|
||||||
|
}
|
||||||
|
|
||||||
Future<void> _runInitSequence() async {
|
Future<void> _runInitSequence() async {
|
||||||
// Load config first
|
// Show all items from the start so the row doesn't jump around
|
||||||
setState(() => _initStatus = 'Loading config...');
|
_updateStatus('Config', '...');
|
||||||
|
_updateStatus('UART', '...');
|
||||||
|
_updateStatus('GPS', '...');
|
||||||
|
_updateStatus('Navigator', '...');
|
||||||
|
|
||||||
|
// Config must load first (everything else depends on it)
|
||||||
|
_updateStatus('Config', 'Loading');
|
||||||
await ConfigService.instance.load();
|
await ConfigService.instance.load();
|
||||||
|
_updateStatus('Config', 'Ready');
|
||||||
|
|
||||||
setState(() => _initStatus = 'Checking systems...');
|
// UART, GPS, and navigator image preload run truly in parallel
|
||||||
|
_updateStatus('UART', 'Connecting');
|
||||||
|
_updateStatus('GPS', 'Waiting');
|
||||||
|
_updateStatus('Navigator', 'Loading');
|
||||||
|
await Future.wait([
|
||||||
|
_waitForUart(),
|
||||||
|
_waitForGps(),
|
||||||
|
_preloadNavigatorImages(),
|
||||||
|
]);
|
||||||
|
|
||||||
|
// Let the user see the all-ready state for a moment
|
||||||
await Future.delayed(const Duration(milliseconds: 500));
|
await Future.delayed(const Duration(milliseconds: 500));
|
||||||
|
|
||||||
// Check UART connection via backend health endpoint
|
|
||||||
setState(() => _initStatus = 'UART: connecting...');
|
|
||||||
await _waitForUart();
|
|
||||||
|
|
||||||
setState(() => _initStatus = 'GPS: standby');
|
|
||||||
await Future.delayed(const Duration(milliseconds: 400));
|
|
||||||
|
|
||||||
setState(() => _initStatus = 'Ready');
|
|
||||||
await Future.delayed(const Duration(milliseconds: 300));
|
|
||||||
|
|
||||||
// Start overheat monitoring
|
// Start overheat monitoring
|
||||||
OverheatMonitor.instance.start(
|
OverheatMonitor.instance.start(
|
||||||
onOverheat: () {
|
onOverheat: () {
|
||||||
@@ -75,11 +86,8 @@ class _AppRootState extends State<AppRoot> {
|
|||||||
|
|
||||||
if (response.statusCode == 200) {
|
if (response.statusCode == 200) {
|
||||||
final data = jsonDecode(response.body) as Map<String, dynamic>;
|
final data = jsonDecode(response.body) as Map<String, dynamic>;
|
||||||
final arduinoOk = data['arduino_connected'] == true;
|
if (data['arduino_connected'] == true) {
|
||||||
|
_updateStatus('UART', 'Ready');
|
||||||
if (arduinoOk) {
|
|
||||||
setState(() => _initStatus = 'UART: OK');
|
|
||||||
await Future.delayed(const Duration(milliseconds: 300));
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -87,14 +95,57 @@ class _AppRootState extends State<AppRoot> {
|
|||||||
// Backend not reachable yet - keep trying
|
// Backend not reachable yet - keep trying
|
||||||
}
|
}
|
||||||
|
|
||||||
// Not connected yet
|
_updateStatus('UART', 'Waiting');
|
||||||
setState(() => _initStatus = 'UART: waiting...');
|
|
||||||
await Future.delayed(retryDelay);
|
await Future.delayed(retryDelay);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Timeout - proceed anyway (UI will show stale data indicators)
|
// Timeout - proceed anyway (UI will show stale data indicators)
|
||||||
setState(() => _initStatus = 'UART: timeout');
|
_updateStatus('UART', 'Timeout');
|
||||||
await Future.delayed(const Duration(milliseconds: 500));
|
}
|
||||||
|
|
||||||
|
/// Poll backend health endpoint until GPS has a fix, or bail after 7.5s
|
||||||
|
Future<void> _waitForGps() async {
|
||||||
|
final backendUrl = ConfigService.instance.backendUrl;
|
||||||
|
const bailOut = Duration(milliseconds: 7500);
|
||||||
|
const retryDelay = Duration(seconds: 1);
|
||||||
|
final deadline = DateTime.now().add(bailOut);
|
||||||
|
|
||||||
|
_updateStatus('GPS', 'Acquiring');
|
||||||
|
|
||||||
|
while (DateTime.now().isBefore(deadline)) {
|
||||||
|
try {
|
||||||
|
final response = await http
|
||||||
|
.get(Uri.parse('$backendUrl/health'))
|
||||||
|
.timeout(const Duration(seconds: 2));
|
||||||
|
|
||||||
|
if (response.statusCode == 200) {
|
||||||
|
final data = jsonDecode(response.body) as Map<String, dynamic>;
|
||||||
|
if (data['gps_state'] == 'fix') {
|
||||||
|
_updateStatus('GPS', 'Ready');
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} catch (e) {
|
||||||
|
// Backend not reachable yet - keep trying
|
||||||
|
}
|
||||||
|
|
||||||
|
await Future.delayed(retryDelay);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Bail out - dashboard will show live GPS state when it arrives
|
||||||
|
_updateStatus('GPS', 'Timeout');
|
||||||
|
}
|
||||||
|
|
||||||
|
/// Preload navigator images into Flutter's image cache
|
||||||
|
///
|
||||||
|
/// Scans for all PNGs in the navigator folder and precaches them.
|
||||||
|
Future<void> _preloadNavigatorImages() async {
|
||||||
|
final images = await ConfigService.instance.getNavigatorImages();
|
||||||
|
for (final file in images) {
|
||||||
|
if (!mounted) return;
|
||||||
|
await precacheImage(FileImage(file), context);
|
||||||
|
}
|
||||||
|
_updateStatus('Navigator', 'Ready');
|
||||||
}
|
}
|
||||||
|
|
||||||
@override
|
@override
|
||||||
@@ -104,7 +155,7 @@ class _AppRootState extends State<AppRoot> {
|
|||||||
if (_overheatTriggered) {
|
if (_overheatTriggered) {
|
||||||
child = const OverheatScreen(key: ValueKey('overheat'));
|
child = const OverheatScreen(key: ValueKey('overheat'));
|
||||||
} else if (!_initialized) {
|
} else if (!_initialized) {
|
||||||
child = SplashScreen(key: const ValueKey('splash'), status: _initStatus);
|
child = SplashScreen(key: const ValueKey('splash'), statuses: _initStatuses);
|
||||||
} else {
|
} else {
|
||||||
child = const DashboardScreen(key: ValueKey('dashboard'));
|
child = const DashboardScreen(key: ValueKey('dashboard'));
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,4 +1,5 @@
|
|||||||
import 'dart:async';
|
import 'dart:async';
|
||||||
|
import 'dart:math' show sqrt, sin, cos, pi;
|
||||||
import 'package:flutter/material.dart';
|
import 'package:flutter/material.dart';
|
||||||
|
|
||||||
import '../services/backend_service.dart';
|
import '../services/backend_service.dart';
|
||||||
@@ -11,6 +12,8 @@ import '../widgets/stat_box_main.dart';
|
|||||||
import '../widgets/system_bar.dart';
|
import '../widgets/system_bar.dart';
|
||||||
import '../widgets/debug_console.dart';
|
import '../widgets/debug_console.dart';
|
||||||
import '../widgets/whiskey_mark.dart';
|
import '../widgets/whiskey_mark.dart';
|
||||||
|
import '../widgets/accel_graph.dart';
|
||||||
|
import '../widgets/gps_compass.dart';
|
||||||
|
|
||||||
// test service for triggers
|
// test service for triggers
|
||||||
import '../services/test_flipflop_service.dart';
|
import '../services/test_flipflop_service.dart';
|
||||||
@@ -24,6 +27,8 @@ class DashboardScreen extends StatefulWidget {
|
|||||||
}
|
}
|
||||||
|
|
||||||
class _DashboardScreenState extends State<DashboardScreen> {
|
class _DashboardScreenState extends State<DashboardScreen> {
|
||||||
|
static const _surpriseThreshold = 0.24; // G threshold for navigator surprise
|
||||||
|
|
||||||
final _navigatorKey = GlobalKey<NavigatorWidgetState>();
|
final _navigatorKey = GlobalKey<NavigatorWidgetState>();
|
||||||
|
|
||||||
// Timer for Pi temp only (safety critical, direct file read)
|
// Timer for Pi temp only (safety critical, direct file read)
|
||||||
@@ -32,6 +37,7 @@ class _DashboardScreenState extends State<DashboardScreen> {
|
|||||||
// WebSocket stream subscriptions
|
// WebSocket stream subscriptions
|
||||||
StreamSubscription<ArduinoData>? _arduinoSub;
|
StreamSubscription<ArduinoData>? _arduinoSub;
|
||||||
StreamSubscription<GpsData>? _gpsSub;
|
StreamSubscription<GpsData>? _gpsSub;
|
||||||
|
StreamSubscription<LteData>? _lteSub;
|
||||||
StreamSubscription<WsConnectionState>? _connectionSub;
|
StreamSubscription<WsConnectionState>? _connectionSub;
|
||||||
|
|
||||||
// Pi temperature - direct file read (safety critical)
|
// Pi temperature - direct file read (safety critical)
|
||||||
@@ -44,12 +50,18 @@ class _DashboardScreenState extends State<DashboardScreen> {
|
|||||||
int? _gear;
|
int? _gear;
|
||||||
double? _roll;
|
double? _roll;
|
||||||
double? _pitch;
|
double? _pitch;
|
||||||
|
double? _ax;
|
||||||
|
double? _ay;
|
||||||
|
double? _dynamicAx; // Gravity-compensated
|
||||||
|
double? _dynamicAy;
|
||||||
|
|
||||||
// From backend - GPS data
|
// From backend - GPS data
|
||||||
double? _gpsSpeed;
|
double? _gpsSpeed;
|
||||||
|
double? _gpsTrack;
|
||||||
|
|
||||||
// Placeholder values for system bar
|
// Placeholder values for system bar
|
||||||
int? _gpsSatellites;
|
int? _gpsSatellites;
|
||||||
|
String? _gpsState;
|
||||||
int? _lteSignal;
|
int? _lteSignal;
|
||||||
|
|
||||||
// WebSocket connection state
|
// WebSocket connection state
|
||||||
@@ -64,6 +76,16 @@ class _DashboardScreenState extends State<DashboardScreen> {
|
|||||||
|
|
||||||
// Subscribe to Arduino data stream
|
// Subscribe to Arduino data stream
|
||||||
_arduinoSub = WebSocketService.instance.arduinoStream.listen((data) {
|
_arduinoSub = WebSocketService.instance.arduinoStream.listen((data) {
|
||||||
|
// Gravity-compensated acceleration
|
||||||
|
// When tilted, gravity "leaks" into horizontal axes - subtract it out
|
||||||
|
final rollRad = (data.roll ?? 0) * pi / 180;
|
||||||
|
final pitchRad = (data.pitch ?? 0) * pi / 180;
|
||||||
|
|
||||||
|
// Subtract gravity leakage from measured acceleration
|
||||||
|
// Axes swapped for IMU mounting orientation
|
||||||
|
final dynamicAx = (data.ay ?? 0) + sin(rollRad);
|
||||||
|
final dynamicAy = (data.ax ?? 0) - (sin(pitchRad) * cos(rollRad));
|
||||||
|
|
||||||
setState(() {
|
setState(() {
|
||||||
_voltage = data.voltage;
|
_voltage = data.voltage;
|
||||||
_rpm = data.rpm;
|
_rpm = data.rpm;
|
||||||
@@ -71,15 +93,32 @@ class _DashboardScreenState extends State<DashboardScreen> {
|
|||||||
_gear = data.gear;
|
_gear = data.gear;
|
||||||
_roll = data.roll;
|
_roll = data.roll;
|
||||||
_pitch = data.pitch;
|
_pitch = data.pitch;
|
||||||
|
_ax = data.ax;
|
||||||
|
_ay = data.ay;
|
||||||
|
_dynamicAx = dynamicAx;
|
||||||
|
_dynamicAy = dynamicAy;
|
||||||
});
|
});
|
||||||
|
|
||||||
|
final gMagnitude = sqrt(dynamicAx * dynamicAx + dynamicAy * dynamicAy);
|
||||||
|
if (gMagnitude > _surpriseThreshold) {
|
||||||
|
_navigatorKey.currentState?.setEmotion('surprise');
|
||||||
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
// Subscribe to GPS data stream
|
// Subscribe to GPS data stream
|
||||||
_gpsSub = WebSocketService.instance.gpsStream.listen((data) {
|
_gpsSub = WebSocketService.instance.gpsStream.listen((data) {
|
||||||
setState(() {
|
setState(() {
|
||||||
_gpsSpeed = data.speed;
|
_gpsSpeed = data.speed;
|
||||||
// Derive satellites from mode (placeholder logic)
|
_gpsTrack = data.track;
|
||||||
_gpsSatellites = data.mode == 3 ? 8 : (data.mode == 2 ? 4 : 0);
|
_gpsSatellites = data.satellites;
|
||||||
|
_gpsState = data.gpsState;
|
||||||
|
});
|
||||||
|
});
|
||||||
|
|
||||||
|
// Subscribe to LTE data stream
|
||||||
|
_lteSub = WebSocketService.instance.lteStream.listen((data) {
|
||||||
|
setState(() {
|
||||||
|
_lteSignal = data.signal;
|
||||||
});
|
});
|
||||||
});
|
});
|
||||||
|
|
||||||
@@ -106,18 +145,25 @@ class _DashboardScreenState extends State<DashboardScreen> {
|
|||||||
_gear = cachedArduino.gear;
|
_gear = cachedArduino.gear;
|
||||||
_roll = cachedArduino.roll;
|
_roll = cachedArduino.roll;
|
||||||
_pitch = cachedArduino.pitch;
|
_pitch = cachedArduino.pitch;
|
||||||
|
_ax = cachedArduino.ax;
|
||||||
|
_ay = cachedArduino.ay;
|
||||||
}
|
}
|
||||||
|
|
||||||
final cachedGps = WebSocketService.instance.latestGps;
|
final cachedGps = WebSocketService.instance.latestGps;
|
||||||
if (cachedGps != null) {
|
if (cachedGps != null) {
|
||||||
_gpsSpeed = cachedGps.speed;
|
_gpsSpeed = cachedGps.speed;
|
||||||
_gpsSatellites = cachedGps.mode == 3 ? 8 : (cachedGps.mode == 2 ? 4 : 0);
|
_gpsTrack = cachedGps.track;
|
||||||
|
_gpsSatellites = cachedGps.satellites;
|
||||||
|
_gpsState = cachedGps.gpsState;
|
||||||
}
|
}
|
||||||
|
|
||||||
_wsState = WebSocketService.instance.connectionState;
|
_wsState = WebSocketService.instance.connectionState;
|
||||||
|
|
||||||
// Placeholder: LTE signal (TODO: wire up when LTE service exists)
|
// Init from cached LTE data
|
||||||
_lteSignal = null;
|
final cachedLte = WebSocketService.instance.latestLte;
|
||||||
|
if (cachedLte != null) {
|
||||||
|
_lteSignal = cachedLte.signal;
|
||||||
|
}
|
||||||
|
|
||||||
// DEBUG: flip-flop theme + navigator every 2s
|
// DEBUG: flip-flop theme + navigator every 2s
|
||||||
TestFlipFlopService.instance.start(navigatorKey: _navigatorKey);
|
TestFlipFlopService.instance.start(navigatorKey: _navigatorKey);
|
||||||
@@ -128,6 +174,7 @@ class _DashboardScreenState extends State<DashboardScreen> {
|
|||||||
_piTempTimer?.cancel();
|
_piTempTimer?.cancel();
|
||||||
_arduinoSub?.cancel();
|
_arduinoSub?.cancel();
|
||||||
_gpsSub?.cancel();
|
_gpsSub?.cancel();
|
||||||
|
_lteSub?.cancel();
|
||||||
_connectionSub?.cancel();
|
_connectionSub?.cancel();
|
||||||
TestFlipFlopService.instance.stop();
|
TestFlipFlopService.instance.stop();
|
||||||
super.dispose();
|
super.dispose();
|
||||||
@@ -168,24 +215,18 @@ class _DashboardScreenState extends State<DashboardScreen> {
|
|||||||
// System status bar
|
// System status bar
|
||||||
SystemBar(
|
SystemBar(
|
||||||
gpsSatellites: _gpsSatellites,
|
gpsSatellites: _gpsSatellites,
|
||||||
|
gpsState: _gpsState,
|
||||||
lteSignal: _lteSignal,
|
lteSignal: _lteSignal,
|
||||||
piTemp: _piTemp,
|
piTemp: _piTemp,
|
||||||
voltage: _voltage,
|
voltage: _voltage,
|
||||||
wsState: _wsState,
|
wsState: _wsState,
|
||||||
),
|
),
|
||||||
|
|
||||||
const SizedBox(height: 5),
|
// Main content area - big widgets
|
||||||
|
|
||||||
// Main content area - big stat boxes
|
|
||||||
Expanded(
|
Expanded(
|
||||||
flex: 8,
|
flex: 7,
|
||||||
child: Row(
|
child: Row(
|
||||||
children: [
|
children: [
|
||||||
// RPM from Arduino
|
|
||||||
// StatBoxMain(
|
|
||||||
// value: _formatInt(_rpm),
|
|
||||||
// label: 'RPM',
|
|
||||||
// ),
|
|
||||||
// Attitude indicator (whiskey mark)
|
// Attitude indicator (whiskey mark)
|
||||||
Expanded(
|
Expanded(
|
||||||
child: WhiskeyMark(
|
child: WhiskeyMark(
|
||||||
@@ -193,18 +234,26 @@ class _DashboardScreenState extends State<DashboardScreen> {
|
|||||||
pitch: _pitch,
|
pitch: _pitch,
|
||||||
),
|
),
|
||||||
),
|
),
|
||||||
|
Expanded(
|
||||||
|
child: AccelGraph(
|
||||||
|
ax: _dynamicAx, // Gravity-compensated lateral
|
||||||
|
ay: _dynamicAy, // Gravity-compensated longitudinal
|
||||||
|
maxG: 0.8,
|
||||||
|
ghostTrackPeriod: const Duration(seconds: 4),
|
||||||
|
),
|
||||||
|
)
|
||||||
],
|
],
|
||||||
),
|
),
|
||||||
),
|
),
|
||||||
|
|
||||||
// Bottom stats row
|
// Bottom stats row
|
||||||
Expanded(
|
Expanded(
|
||||||
flex: 2,
|
flex: 3,
|
||||||
child: Row(
|
child: Row(
|
||||||
mainAxisAlignment: MainAxisAlignment.spaceEvenly,
|
mainAxisAlignment: MainAxisAlignment.spaceEvenly,
|
||||||
children: [
|
children: [
|
||||||
StatBox(value: _formatInt(_rpm), label: 'RPM', isWarning: () => (_rpm ?? 0) > 4000),
|
StatBox(value: _formatInt(_rpm), label: 'RPM', isWarning: () => (_rpm ?? 0) > 4000),
|
||||||
StatBox(value: _formatInt(_engineTemp), unit: '°C', label: 'ENG', isWarning: () => (_engineTemp ?? 0) > 120),
|
GpsCompass(heading: _gpsTrack, gpsState: _gpsState),
|
||||||
StatBox(value: _formatGear(_gear), label: 'GEAR'),
|
StatBox(value: _formatGear(_gear), label: 'GEAR'),
|
||||||
],
|
],
|
||||||
),
|
),
|
||||||
|
|||||||
@@ -3,10 +3,12 @@ import 'package:flutter/material.dart';
|
|||||||
import '../theme/app_theme.dart';
|
import '../theme/app_theme.dart';
|
||||||
|
|
||||||
/// Splash screen - shown during initialization
|
/// Splash screen - shown during initialization
|
||||||
|
///
|
||||||
|
/// Displays parallel status items that independently flip to "Ready".
|
||||||
class SplashScreen extends StatelessWidget {
|
class SplashScreen extends StatelessWidget {
|
||||||
final String status;
|
final Map<String, String> statuses;
|
||||||
|
|
||||||
const SplashScreen({super.key, required this.status});
|
const SplashScreen({super.key, required this.statuses});
|
||||||
|
|
||||||
@override
|
@override
|
||||||
Widget build(BuildContext context) {
|
Widget build(BuildContext context) {
|
||||||
@@ -33,13 +35,19 @@ class SplashScreen extends StatelessWidget {
|
|||||||
fontWeight: FontWeight.bold,
|
fontWeight: FontWeight.bold,
|
||||||
),
|
),
|
||||||
),
|
),
|
||||||
const SizedBox(height: 16),
|
const SizedBox(height: 32),
|
||||||
Text(
|
Row(
|
||||||
status,
|
mainAxisAlignment: MainAxisAlignment.spaceEvenly,
|
||||||
style: Theme.of(context).textTheme.bodyLarge?.copyWith(
|
children: statuses.entries.map((entry) {
|
||||||
fontSize: 80,
|
final isReady = entry.value == 'Ready';
|
||||||
color: theme.subdued,
|
return Text(
|
||||||
),
|
'${entry.key}: ${entry.value}',
|
||||||
|
style: Theme.of(context).textTheme.bodyLarge?.copyWith(
|
||||||
|
fontSize: 48,
|
||||||
|
color: isReady ? theme.foreground : theme.subdued,
|
||||||
|
),
|
||||||
|
);
|
||||||
|
}).toList(),
|
||||||
),
|
),
|
||||||
],
|
],
|
||||||
),
|
),
|
||||||
|
|||||||
@@ -10,8 +10,11 @@ class ArduinoData {
|
|||||||
final int? gear; // 0 = neutral, 1-6 = gear
|
final int? gear; // 0 = neutral, 1-6 = gear
|
||||||
final double? roll; // Euler angle in degrees (negative = left, positive = right)
|
final double? roll; // Euler angle in degrees (negative = left, positive = right)
|
||||||
final double? pitch; // Euler angle in degrees (negative = nose down)
|
final double? pitch; // Euler angle in degrees (negative = nose down)
|
||||||
|
final double? ax; // Lateral acceleration (g)
|
||||||
|
final double? ay; // Longitudinal acceleration (g)
|
||||||
|
final double? az; // Vertical acceleration (g)
|
||||||
|
|
||||||
ArduinoData({this.voltage, this.rpm, this.engTemp, this.gear, this.roll, this.pitch});
|
ArduinoData({this.voltage, this.rpm, this.engTemp, this.gear, this.roll, this.pitch, this.ax, this.ay, this.az});
|
||||||
|
|
||||||
factory ArduinoData.fromJson(Map<String, dynamic> json) {
|
factory ArduinoData.fromJson(Map<String, dynamic> json) {
|
||||||
return ArduinoData(
|
return ArduinoData(
|
||||||
@@ -21,6 +24,9 @@ class ArduinoData {
|
|||||||
gear: (json['gear'] as num?)?.toInt(),
|
gear: (json['gear'] as num?)?.toInt(),
|
||||||
roll: (json['roll'] as num?)?.toDouble(), // IMU mounted with axes swapped
|
roll: (json['roll'] as num?)?.toDouble(), // IMU mounted with axes swapped
|
||||||
pitch: (json['pitch'] as num?)?.toDouble(),
|
pitch: (json['pitch'] as num?)?.toDouble(),
|
||||||
|
ax: (json['ax'] as num?)?.toDouble(),
|
||||||
|
ay: (json['ay'] as num?)?.toDouble(),
|
||||||
|
az: (json['az'] as num?)?.toDouble(),
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -33,8 +39,10 @@ class GpsData {
|
|||||||
final double? alt;
|
final double? alt;
|
||||||
final double? track;
|
final double? track;
|
||||||
final int? mode; // 0=no fix, 2=2D, 3=3D
|
final int? mode; // 0=no fix, 2=2D, 3=3D
|
||||||
|
final int? satellites;
|
||||||
|
final String? gpsState; // "acquiring", "fix", or "lost"
|
||||||
|
|
||||||
GpsData({this.lat, this.lon, this.speed, this.alt, this.track, this.mode});
|
GpsData({this.lat, this.lon, this.speed, this.alt, this.track, this.mode, this.satellites, this.gpsState});
|
||||||
|
|
||||||
factory GpsData.fromJson(Map<String, dynamic> json) {
|
factory GpsData.fromJson(Map<String, dynamic> json) {
|
||||||
return GpsData(
|
return GpsData(
|
||||||
@@ -44,6 +52,27 @@ class GpsData {
|
|||||||
alt: (json['alt'] as num?)?.toDouble(),
|
alt: (json['alt'] as num?)?.toDouble(),
|
||||||
track: (json['track'] as num?)?.toDouble(),
|
track: (json['track'] as num?)?.toDouble(),
|
||||||
mode: (json['mode'] as num?)?.toInt(),
|
mode: (json['mode'] as num?)?.toInt(),
|
||||||
|
satellites: (json['satellites'] as num?)?.toInt(),
|
||||||
|
gpsState: json['gps_state'] as String?,
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/// Data from LTE modem (signal quality, connection state)
|
||||||
|
class LteData {
|
||||||
|
final bool? connected;
|
||||||
|
final int? signal; // 0-100 percent
|
||||||
|
final String? operator_;
|
||||||
|
final String? accessTech;
|
||||||
|
|
||||||
|
LteData({this.connected, this.signal, this.operator_, this.accessTech});
|
||||||
|
|
||||||
|
factory LteData.fromJson(Map<String, dynamic> json) {
|
||||||
|
return LteData(
|
||||||
|
connected: json['connected'] as bool?,
|
||||||
|
signal: (json['signal'] as num?)?.toInt(),
|
||||||
|
operator_: json['operator'] as String?,
|
||||||
|
accessTech: json['access_tech'] as String?,
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -93,4 +93,19 @@ class ConfigService {
|
|||||||
if (value is String && value.isNotEmpty) return value;
|
if (value is String && value.isNotEmpty) return value;
|
||||||
return 'http://127.0.0.1:5000';
|
return 'http://127.0.0.1:5000';
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/// Get list of all navigator image files
|
||||||
|
///
|
||||||
|
/// Scans the navigator directory for PNG files.
|
||||||
|
/// Returns empty list if directory doesn't exist.
|
||||||
|
Future<List<File>> getNavigatorImages() async {
|
||||||
|
final dir = Directory('$assetsPath${Platform.pathSeparator}navigator${Platform.pathSeparator}$navigator');
|
||||||
|
if (!await dir.exists()) return [];
|
||||||
|
|
||||||
|
return dir
|
||||||
|
.listSync()
|
||||||
|
.whereType<File>()
|
||||||
|
.where((f) => f.path.toLowerCase().endsWith('.png'))
|
||||||
|
.toList();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -33,11 +33,11 @@ class TestFlipFlopService {
|
|||||||
// ThemeService.instance.toggle();
|
// ThemeService.instance.toggle();
|
||||||
|
|
||||||
// Surprise the navigator
|
// Surprise the navigator
|
||||||
if (navigatorKey.currentState?.emotion == 'surprise') {
|
// if (navigatorKey.currentState?.emotion == 'surprise') {
|
||||||
navigatorKey.currentState?.reset();
|
// navigatorKey.currentState?.reset();
|
||||||
} else {
|
// } else {
|
||||||
navigatorKey.currentState?.setEmotion('surprise');
|
// navigatorKey.currentState?.setEmotion('surprise');
|
||||||
}
|
// }
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -2,6 +2,7 @@ import 'dart:async';
|
|||||||
import 'package:socket_io_client/socket_io_client.dart' as io;
|
import 'package:socket_io_client/socket_io_client.dart' as io;
|
||||||
|
|
||||||
import 'backend_service.dart'; // Reuse ArduinoData, GpsData
|
import 'backend_service.dart'; // Reuse ArduinoData, GpsData
|
||||||
|
import 'theme_service.dart';
|
||||||
|
|
||||||
/// Connection state for WebSocket
|
/// Connection state for WebSocket
|
||||||
enum WsConnectionState {
|
enum WsConnectionState {
|
||||||
@@ -64,11 +65,13 @@ class WebSocketService {
|
|||||||
// Latest values for sync access (backward compat)
|
// Latest values for sync access (backward compat)
|
||||||
ArduinoData? _latestArduino;
|
ArduinoData? _latestArduino;
|
||||||
GpsData? _latestGps;
|
GpsData? _latestGps;
|
||||||
|
LteData? _latestLte;
|
||||||
BackendStatus? _latestStatus;
|
BackendStatus? _latestStatus;
|
||||||
|
|
||||||
// Stream controllers
|
// Stream controllers
|
||||||
late StreamController<ArduinoData> _arduinoController;
|
late StreamController<ArduinoData> _arduinoController;
|
||||||
late StreamController<GpsData> _gpsController;
|
late StreamController<GpsData> _gpsController;
|
||||||
|
late StreamController<LteData> _lteController;
|
||||||
late StreamController<BackendStatus> _statusController;
|
late StreamController<BackendStatus> _statusController;
|
||||||
late StreamController<CommandAck> _ackController;
|
late StreamController<CommandAck> _ackController;
|
||||||
late StreamController<BackendAlert> _alertController;
|
late StreamController<BackendAlert> _alertController;
|
||||||
@@ -82,6 +85,7 @@ class WebSocketService {
|
|||||||
void _setupStreams() {
|
void _setupStreams() {
|
||||||
_arduinoController = StreamController<ArduinoData>.broadcast();
|
_arduinoController = StreamController<ArduinoData>.broadcast();
|
||||||
_gpsController = StreamController<GpsData>.broadcast();
|
_gpsController = StreamController<GpsData>.broadcast();
|
||||||
|
_lteController = StreamController<LteData>.broadcast();
|
||||||
_statusController = StreamController<BackendStatus>.broadcast();
|
_statusController = StreamController<BackendStatus>.broadcast();
|
||||||
_ackController = StreamController<CommandAck>.broadcast();
|
_ackController = StreamController<CommandAck>.broadcast();
|
||||||
_alertController = StreamController<BackendAlert>.broadcast();
|
_alertController = StreamController<BackendAlert>.broadcast();
|
||||||
@@ -106,6 +110,9 @@ class WebSocketService {
|
|||||||
/// Stream of GPS updates
|
/// Stream of GPS updates
|
||||||
Stream<GpsData> get gpsStream => _gpsController.stream;
|
Stream<GpsData> get gpsStream => _gpsController.stream;
|
||||||
|
|
||||||
|
/// Stream of LTE status updates
|
||||||
|
Stream<LteData> get lteStream => _lteController.stream;
|
||||||
|
|
||||||
/// Stream of backend status updates
|
/// Stream of backend status updates
|
||||||
Stream<BackendStatus> get statusStream => _statusController.stream;
|
Stream<BackendStatus> get statusStream => _statusController.stream;
|
||||||
|
|
||||||
@@ -138,6 +145,9 @@ class WebSocketService {
|
|||||||
/// Latest GPS data (may be null if not yet received)
|
/// Latest GPS data (may be null if not yet received)
|
||||||
GpsData? get latestGps => _latestGps;
|
GpsData? get latestGps => _latestGps;
|
||||||
|
|
||||||
|
/// Latest LTE data (may be null if not yet received)
|
||||||
|
LteData? get latestLte => _latestLte;
|
||||||
|
|
||||||
/// Latest backend status
|
/// Latest backend status
|
||||||
BackendStatus? get latestStatus => _latestStatus;
|
BackendStatus? get latestStatus => _latestStatus;
|
||||||
|
|
||||||
@@ -188,6 +198,13 @@ class WebSocketService {
|
|||||||
final pitchStr = arduino.pitch != null ? 'p${arduino.pitch!.round()}' : '';
|
final pitchStr = arduino.pitch != null ? 'p${arduino.pitch!.round()}' : '';
|
||||||
final imuStr = (rollStr.isNotEmpty || pitchStr.isNotEmpty) ? ' $rollStr$pitchStr' : '';
|
final imuStr = (rollStr.isNotEmpty || pitchStr.isNotEmpty) ? ' $rollStr$pitchStr' : '';
|
||||||
_log('ard: ${arduino.rpm ?? "-"}rpm ${arduino.voltage ?? "-"}V g${arduino.gear ?? "-"}$imuStr');
|
_log('ard: ${arduino.rpm ?? "-"}rpm ${arduino.voltage ?? "-"}V g${arduino.gear ?? "-"}$imuStr');
|
||||||
|
|
||||||
|
// Theme switch piggybacks on arduino packets (edge-triggered from backend)
|
||||||
|
if (data.containsKey('theme_switch')) {
|
||||||
|
final isDark = data['theme_switch'] as bool;
|
||||||
|
ThemeService.instance.setDarkMode(isDark);
|
||||||
|
_log('theme: ${isDark ? "dark" : "light"}');
|
||||||
|
}
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
@@ -196,7 +213,16 @@ class WebSocketService {
|
|||||||
final gps = GpsData.fromJson(data);
|
final gps = GpsData.fromJson(data);
|
||||||
_latestGps = gps;
|
_latestGps = gps;
|
||||||
_gpsController.add(gps);
|
_gpsController.add(gps);
|
||||||
_log('gps: ${gps.speed?.toStringAsFixed(1) ?? "-"}m/s mode${gps.mode ?? "-"}');
|
_log('gps: ${gps.speed?.toStringAsFixed(1) ?? "-"}m/s hdg=${gps.track?.round() ?? "-"}° mode${gps.mode ?? "-"}');
|
||||||
|
}
|
||||||
|
});
|
||||||
|
|
||||||
|
_socket!.on('lte', (data) {
|
||||||
|
if (data is Map<String, dynamic>) {
|
||||||
|
final lte = LteData.fromJson(data);
|
||||||
|
_latestLte = lte;
|
||||||
|
_lteController.add(lte);
|
||||||
|
_log('lte: ${lte.signal ?? "-"}% ${lte.operator_ ?? "-"} ${lte.accessTech ?? "-"}');
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
@@ -209,6 +235,13 @@ class WebSocketService {
|
|||||||
_latestStatus = status;
|
_latestStatus = status;
|
||||||
_statusController.add(status);
|
_statusController.add(status);
|
||||||
_log('status: gps=${status.gpsConnected} ard=${status.arduinoConnected}');
|
_log('status: gps=${status.gpsConnected} ard=${status.arduinoConnected}');
|
||||||
|
|
||||||
|
// Initial theme state comes with status on connect
|
||||||
|
if (data.containsKey('theme_switch')) {
|
||||||
|
final isDark = data['theme_switch'] as bool;
|
||||||
|
ThemeService.instance.setDarkMode(isDark);
|
||||||
|
_log('theme: ${isDark ? "dark" : "light"} (initial)');
|
||||||
|
}
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
|
||||||
@@ -308,6 +341,7 @@ class WebSocketService {
|
|||||||
disconnect();
|
disconnect();
|
||||||
_arduinoController.close();
|
_arduinoController.close();
|
||||||
_gpsController.close();
|
_gpsController.close();
|
||||||
|
_lteController.close();
|
||||||
_statusController.close();
|
_statusController.close();
|
||||||
_ackController.close();
|
_ackController.close();
|
||||||
_alertController.close();
|
_alertController.close();
|
||||||
|
|||||||
333
pi/ui/lib/widgets/accel_graph.dart
Normal file
333
pi/ui/lib/widgets/accel_graph.dart
Normal file
@@ -0,0 +1,333 @@
|
|||||||
|
import 'dart:math' as math;
|
||||||
|
import 'package:flutter/material.dart';
|
||||||
|
|
||||||
|
import '../theme/app_theme.dart';
|
||||||
|
|
||||||
|
/// 2D lateral G-meter showing acceleration as a dot on a cartesian grid.
|
||||||
|
///
|
||||||
|
/// Visual: square grid with dot position = (ax, ay) scaled by maxG
|
||||||
|
/// Optional ghost dot tracks peak magnitude within ghostTrackPeriod window.
|
||||||
|
class AccelGraph extends StatefulWidget {
|
||||||
|
/// X-axis acceleration in g (lateral: negative = left, positive = right)
|
||||||
|
final double? ax;
|
||||||
|
|
||||||
|
/// Y-axis acceleration in g (longitudinal: negative = back, positive = forward)
|
||||||
|
final double? ay;
|
||||||
|
|
||||||
|
/// Maximum G range for the grid (default 2.0 = ±2G)
|
||||||
|
final double maxG;
|
||||||
|
|
||||||
|
/// If set, shows a ghost dot at peak magnitude position, resetting after this duration
|
||||||
|
final Duration? ghostTrackPeriod;
|
||||||
|
|
||||||
|
const AccelGraph({
|
||||||
|
super.key,
|
||||||
|
this.ax,
|
||||||
|
this.ay,
|
||||||
|
this.maxG = 2.0,
|
||||||
|
this.ghostTrackPeriod,
|
||||||
|
});
|
||||||
|
|
||||||
|
@override
|
||||||
|
State<AccelGraph> createState() => _AccelGraphState();
|
||||||
|
}
|
||||||
|
|
||||||
|
class _AccelGraphState extends State<AccelGraph> {
|
||||||
|
// Ghost dot tracking
|
||||||
|
double _ghostAx = 0;
|
||||||
|
double _ghostAy = 0;
|
||||||
|
double _ghostMagnitude = 0;
|
||||||
|
|
||||||
|
// Timestamped history for sliding window
|
||||||
|
List<({DateTime time, double ax, double ay})> _history = [];
|
||||||
|
|
||||||
|
@override
|
||||||
|
void didUpdateWidget(AccelGraph oldWidget) {
|
||||||
|
super.didUpdateWidget(oldWidget);
|
||||||
|
|
||||||
|
final currentAx = widget.ax ?? 0;
|
||||||
|
final currentAy = widget.ay ?? 0;
|
||||||
|
final now = DateTime.now();
|
||||||
|
|
||||||
|
// Only track history when ghostTrackPeriod is configured
|
||||||
|
if (widget.ghostTrackPeriod != null) {
|
||||||
|
// Add current reading to history
|
||||||
|
_history.add((time: now, ax: currentAx, ay: currentAy));
|
||||||
|
|
||||||
|
// Prune entries outside the window
|
||||||
|
final cutoff = now.subtract(widget.ghostTrackPeriod!);
|
||||||
|
_history.removeWhere((e) => e.time.isBefore(cutoff));
|
||||||
|
|
||||||
|
// Recalculate ghost as max magnitude from current window
|
||||||
|
_ghostAx = currentAx;
|
||||||
|
_ghostAy = currentAy;
|
||||||
|
_ghostMagnitude = 0;
|
||||||
|
|
||||||
|
for (final entry in _history) {
|
||||||
|
final mag = math.sqrt(entry.ax * entry.ax + entry.ay * entry.ay);
|
||||||
|
if (mag > _ghostMagnitude) {
|
||||||
|
_ghostAx = entry.ax;
|
||||||
|
_ghostAy = entry.ay;
|
||||||
|
_ghostMagnitude = mag;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
// No window configured - clear history to save memory
|
||||||
|
_history.clear();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
@override
|
||||||
|
Widget build(BuildContext context) {
|
||||||
|
final theme = AppTheme.of(context);
|
||||||
|
|
||||||
|
return LayoutBuilder(
|
||||||
|
builder: (context, constraints) {
|
||||||
|
final size = math.min(constraints.maxWidth, constraints.maxHeight);
|
||||||
|
final gridSize = size * 0.6;
|
||||||
|
final fontSize = size * 0.12;
|
||||||
|
final strokeSize = size * 0.015;
|
||||||
|
|
||||||
|
return Column(
|
||||||
|
mainAxisAlignment: MainAxisAlignment.center,
|
||||||
|
children: [
|
||||||
|
// G-meter grid
|
||||||
|
SizedBox(
|
||||||
|
width: gridSize,
|
||||||
|
height: gridSize,
|
||||||
|
child: CustomPaint(
|
||||||
|
painter: _AccelGraphPainter(
|
||||||
|
ax: widget.ax ?? 0,
|
||||||
|
ay: widget.ay ?? 0,
|
||||||
|
ghostAx: _ghostAx,
|
||||||
|
ghostAy: _ghostAy,
|
||||||
|
showGhost: widget.ghostTrackPeriod != null && _ghostMagnitude > 0,
|
||||||
|
maxG: widget.maxG,
|
||||||
|
foreground: theme.foreground,
|
||||||
|
subdued: theme.subdued,
|
||||||
|
background: theme.background,
|
||||||
|
strokeWeight: strokeSize,
|
||||||
|
traceBuffer: _history.map((e) => Offset(e.ax, e.ay)).toList(),
|
||||||
|
),
|
||||||
|
),
|
||||||
|
),
|
||||||
|
|
||||||
|
SizedBox(height: size * 0.03),
|
||||||
|
|
||||||
|
// Numeric readout
|
||||||
|
Row(
|
||||||
|
mainAxisAlignment: MainAxisAlignment.center,
|
||||||
|
children: [
|
||||||
|
Text(
|
||||||
|
'Lon: ${_formatAccel(widget.ay)} (${_formatAccel(_ghostAy)})',
|
||||||
|
style: TextStyle(
|
||||||
|
fontSize: fontSize * 0.5,
|
||||||
|
fontWeight: FontWeight.w400,
|
||||||
|
fontFeatures: const [FontFeature.tabularFigures()],
|
||||||
|
color: theme.foreground,
|
||||||
|
),
|
||||||
|
),
|
||||||
|
SizedBox(width: size * 0.1),
|
||||||
|
Text(
|
||||||
|
'Lat: ${_formatAccel(widget.ax)} (${_formatAccel(_ghostAx)})',
|
||||||
|
style: TextStyle(
|
||||||
|
fontSize: fontSize * 0.5,
|
||||||
|
fontWeight: FontWeight.w400,
|
||||||
|
fontFeatures: const [FontFeature.tabularFigures()],
|
||||||
|
color: theme.subdued,
|
||||||
|
),
|
||||||
|
),
|
||||||
|
],
|
||||||
|
),
|
||||||
|
|
||||||
|
// Label
|
||||||
|
Text(
|
||||||
|
'Acceleration',
|
||||||
|
style: TextStyle(
|
||||||
|
fontSize: fontSize * 0.8,
|
||||||
|
fontWeight: FontWeight.w400,
|
||||||
|
color: theme.subdued,
|
||||||
|
letterSpacing: 1,
|
||||||
|
),
|
||||||
|
),
|
||||||
|
],
|
||||||
|
);
|
||||||
|
},
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
String _formatAccel(double? force) {
|
||||||
|
if (force == null) return '—°';
|
||||||
|
return '${
|
||||||
|
force.toStringAsFixed(1) == '-0.0' ? '0.0' : force.toStringAsFixed(1)
|
||||||
|
}G';
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/// Custom painter for the G-meter grid and dots
|
||||||
|
class _AccelGraphPainter extends CustomPainter {
|
||||||
|
final double ax;
|
||||||
|
final double ay;
|
||||||
|
final double ghostAx;
|
||||||
|
final double ghostAy;
|
||||||
|
final bool showGhost;
|
||||||
|
final double maxG;
|
||||||
|
final Color foreground;
|
||||||
|
final Color subdued;
|
||||||
|
final Color background;
|
||||||
|
final double strokeWeight;
|
||||||
|
final List<Offset> traceBuffer;
|
||||||
|
|
||||||
|
_AccelGraphPainter({
|
||||||
|
required this.ax,
|
||||||
|
required this.ay,
|
||||||
|
required this.ghostAx,
|
||||||
|
required this.ghostAy,
|
||||||
|
required this.showGhost,
|
||||||
|
required this.maxG,
|
||||||
|
required this.foreground,
|
||||||
|
required this.subdued,
|
||||||
|
required this.background,
|
||||||
|
required this.strokeWeight,
|
||||||
|
required this.traceBuffer,
|
||||||
|
});
|
||||||
|
|
||||||
|
@override
|
||||||
|
void paint(Canvas canvas, Size size) {
|
||||||
|
final center = Offset(size.width / 2, size.height / 2);
|
||||||
|
final halfSize = size.width / 2;
|
||||||
|
final radius = math.min(size.width, size.height) / 2;
|
||||||
|
|
||||||
|
canvas.clipPath(Path()..addOval(Rect.fromCircle(center: center, radius: radius)));
|
||||||
|
|
||||||
|
// No rectangular border
|
||||||
|
|
||||||
|
// Grid lines at 0.25G intervals
|
||||||
|
final gridPaint = Paint()
|
||||||
|
..color = subdued
|
||||||
|
..strokeWidth = strokeWeight * 0.4
|
||||||
|
..style = PaintingStyle.stroke;
|
||||||
|
|
||||||
|
final gStep = 0.25;
|
||||||
|
for (double g = gStep; g < maxG; g += gStep) {
|
||||||
|
final offset = (g / maxG) * halfSize;
|
||||||
|
|
||||||
|
// Vertical lines (left and right of center)
|
||||||
|
canvas.drawLine(
|
||||||
|
Offset(center.dx - offset, 0),
|
||||||
|
Offset(center.dx - offset, size.height),
|
||||||
|
gridPaint,
|
||||||
|
);
|
||||||
|
canvas.drawLine(
|
||||||
|
Offset(center.dx + offset, 0),
|
||||||
|
Offset(center.dx + offset, size.height),
|
||||||
|
gridPaint,
|
||||||
|
);
|
||||||
|
|
||||||
|
// Horizontal lines (above and below center)
|
||||||
|
canvas.drawLine(
|
||||||
|
Offset(0, center.dy - offset),
|
||||||
|
Offset(size.width, center.dy - offset),
|
||||||
|
gridPaint,
|
||||||
|
);
|
||||||
|
canvas.drawLine(
|
||||||
|
Offset(0, center.dy + offset),
|
||||||
|
Offset(size.width, center.dy + offset),
|
||||||
|
gridPaint,
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Center axis lines (heavier)
|
||||||
|
final axisPaint = Paint()
|
||||||
|
..color = subdued
|
||||||
|
..strokeWidth = strokeWeight
|
||||||
|
..style = PaintingStyle.stroke;
|
||||||
|
|
||||||
|
// Horizontal axis
|
||||||
|
canvas.drawLine(
|
||||||
|
Offset(0, center.dy),
|
||||||
|
Offset(size.width, center.dy),
|
||||||
|
axisPaint,
|
||||||
|
);
|
||||||
|
// Vertical axis
|
||||||
|
canvas.drawLine(
|
||||||
|
Offset(center.dx, 0),
|
||||||
|
Offset(center.dx, size.height),
|
||||||
|
axisPaint,
|
||||||
|
);
|
||||||
|
|
||||||
|
// G-ring markers (circles at every 0.5G for quick reference)
|
||||||
|
final ringPaint = Paint()
|
||||||
|
..color = subdued
|
||||||
|
..strokeWidth = strokeWeight * 0.5
|
||||||
|
..style = PaintingStyle.stroke;
|
||||||
|
|
||||||
|
for (double g = 0.5; g <= maxG; g += 0.5) {
|
||||||
|
final radius = (g / maxG) * halfSize;
|
||||||
|
canvas.drawCircle(center, radius, ringPaint);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Trace line
|
||||||
|
if (traceBuffer.length >= 2) {
|
||||||
|
final tracePaint = Paint()
|
||||||
|
..color = foreground
|
||||||
|
..strokeWidth = strokeWeight * 0.4
|
||||||
|
..style = PaintingStyle.stroke
|
||||||
|
..strokeCap = StrokeCap.round
|
||||||
|
..strokeJoin = StrokeJoin.round;
|
||||||
|
|
||||||
|
final path = Path();
|
||||||
|
for (int i = 0; i < traceBuffer.length; i++) {
|
||||||
|
final pt = traceBuffer[i];
|
||||||
|
final x = center.dx + (pt.dx.clamp(-maxG, maxG) / maxG) * halfSize;
|
||||||
|
final y = center.dy - (pt.dy.clamp(-maxG, maxG) / maxG) * halfSize;
|
||||||
|
if (i == 0) {
|
||||||
|
path.moveTo(x, y);
|
||||||
|
} else {
|
||||||
|
path.lineTo(x, y);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
canvas.drawPath(path, tracePaint);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Ghost dot (if enabled and has data)
|
||||||
|
if (showGhost) {
|
||||||
|
final ghostX = center.dx + (ghostAx / maxG) * halfSize;
|
||||||
|
final ghostY = center.dy - (ghostAy / maxG) * halfSize; // Y inverted (up = positive)
|
||||||
|
final ghostRadius = halfSize * 0.08;
|
||||||
|
|
||||||
|
final ghostPaint = Paint()
|
||||||
|
..color = subdued
|
||||||
|
..strokeWidth = strokeWeight
|
||||||
|
..style = PaintingStyle.stroke;
|
||||||
|
|
||||||
|
canvas.drawCircle(Offset(ghostX, ghostY), ghostRadius, ghostPaint);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Main dot - clamp to grid bounds
|
||||||
|
final clampedAx = ax.clamp(-maxG, maxG);
|
||||||
|
final clampedAy = ay.clamp(-maxG, maxG);
|
||||||
|
final dotX = center.dx + (clampedAx / maxG) * halfSize;
|
||||||
|
final dotY = center.dy - (clampedAy / maxG) * halfSize; // Y inverted (up = positive)
|
||||||
|
final dotRadius = halfSize * 0.1;
|
||||||
|
|
||||||
|
final dotPaint = Paint()
|
||||||
|
..color = foreground
|
||||||
|
..style = PaintingStyle.fill;
|
||||||
|
|
||||||
|
canvas.drawCircle(Offset(dotX, dotY), dotRadius, dotPaint);
|
||||||
|
}
|
||||||
|
|
||||||
|
@override
|
||||||
|
bool shouldRepaint(_AccelGraphPainter oldDelegate) {
|
||||||
|
return ax != oldDelegate.ax ||
|
||||||
|
ay != oldDelegate.ay ||
|
||||||
|
ghostAx != oldDelegate.ghostAx ||
|
||||||
|
ghostAy != oldDelegate.ghostAy ||
|
||||||
|
showGhost != oldDelegate.showGhost ||
|
||||||
|
maxG != oldDelegate.maxG ||
|
||||||
|
foreground != oldDelegate.foreground ||
|
||||||
|
subdued != oldDelegate.subdued ||
|
||||||
|
traceBuffer != oldDelegate.traceBuffer;
|
||||||
|
}
|
||||||
|
}
|
||||||
73
pi/ui/lib/widgets/gps_compass.dart
Normal file
73
pi/ui/lib/widgets/gps_compass.dart
Normal file
@@ -0,0 +1,73 @@
|
|||||||
|
import 'dart:math' as math;
|
||||||
|
import 'package:flutter/material.dart';
|
||||||
|
import '../theme/app_theme.dart';
|
||||||
|
|
||||||
|
class GpsCompass extends StatelessWidget {
|
||||||
|
final double? heading;
|
||||||
|
final String? gpsState; // "acquiring", "fix", "lost"
|
||||||
|
|
||||||
|
const GpsCompass({super.key, this.heading, this.gpsState});
|
||||||
|
|
||||||
|
bool get _hasSignal => heading != null;
|
||||||
|
bool get _isAcquiring => gpsState == 'acquiring';
|
||||||
|
|
||||||
|
String get _displayHeading {
|
||||||
|
if (!_hasSignal) return 'N/A';
|
||||||
|
return '${(heading! % 360).round()}';
|
||||||
|
}
|
||||||
|
|
||||||
|
String get _compassDirection {
|
||||||
|
if (!_hasSignal) return '';
|
||||||
|
final directions = [
|
||||||
|
'N', 'NNE', 'NE', 'ENE', 'E', 'ESE', 'SE', 'SSE',
|
||||||
|
'S', 'SSW', 'SW', 'WSW', 'W', 'WNW', 'NW', 'NNW'
|
||||||
|
];
|
||||||
|
final index = ((heading! % 360) / 22.5).round() % 16;
|
||||||
|
return directions[index];
|
||||||
|
}
|
||||||
|
|
||||||
|
@override
|
||||||
|
Widget build(BuildContext context) {
|
||||||
|
final theme = AppTheme.of(context);
|
||||||
|
|
||||||
|
// No signal = subdued color, valid = foreground
|
||||||
|
final iconColour = _hasSignal ? theme.foreground : theme.highlight;
|
||||||
|
|
||||||
|
// Convert to radians, 0 = no rotation when no signal
|
||||||
|
final angle = _hasSignal ? (heading! * math.pi / 180.0) : 0.0;
|
||||||
|
|
||||||
|
return Column(
|
||||||
|
mainAxisAlignment: MainAxisAlignment.center,
|
||||||
|
children: [
|
||||||
|
Flexible(
|
||||||
|
flex: 3,
|
||||||
|
child: Transform.rotate(
|
||||||
|
angle: _hasSignal ? angle : 0,
|
||||||
|
child: FittedBox(
|
||||||
|
fit: BoxFit.contain,
|
||||||
|
child: Icon(
|
||||||
|
_hasSignal ? Icons.navigation : Icons.navigation_outlined,
|
||||||
|
size: 120,
|
||||||
|
color: iconColour,
|
||||||
|
),
|
||||||
|
),
|
||||||
|
),
|
||||||
|
),
|
||||||
|
Flexible(
|
||||||
|
flex: 1,
|
||||||
|
child: FittedBox(
|
||||||
|
fit: BoxFit.contain,
|
||||||
|
child: Text(
|
||||||
|
_hasSignal ? "${_displayHeading} ${_compassDirection}" : (_isAcquiring ? "ACQ" : "N/A"),
|
||||||
|
style: TextStyle(
|
||||||
|
fontSize: 80,
|
||||||
|
color: theme.subdued, // less emphasis on text, let the icon have semantic colour
|
||||||
|
fontFamily: 'DIN1451',
|
||||||
|
),
|
||||||
|
),
|
||||||
|
),
|
||||||
|
),
|
||||||
|
],
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -31,6 +31,12 @@ class NavigatorWidgetState extends State<NavigatorWidget>
|
|||||||
duration: const Duration(milliseconds: 400),
|
duration: const Duration(milliseconds: 400),
|
||||||
vsync: this,
|
vsync: this,
|
||||||
);
|
);
|
||||||
|
// Auto-reset to default after surprise animation completes
|
||||||
|
_shakeController.addStatusListener((status) {
|
||||||
|
if (status == AnimationStatus.completed && _emotion == 'surprise') {
|
||||||
|
setState(() => _emotion = 'default');
|
||||||
|
}
|
||||||
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
@override
|
@override
|
||||||
@@ -82,8 +88,8 @@ class NavigatorWidgetState extends State<NavigatorWidget>
|
|||||||
animation: _shakeController,
|
animation: _shakeController,
|
||||||
child: image,
|
child: image,
|
||||||
builder: (context, child) {
|
builder: (context, child) {
|
||||||
final shake = sin(_shakeController.value * pi * 6) * 10 *
|
final shake = sin(_shakeController.value * pi * 6) * 25 *
|
||||||
(1 - _shakeController.value); // 6 oscillations, 4px amplitude, decay
|
(1 - _shakeController.value); // 6 oscillations, 25px amplitude, decay
|
||||||
return Transform.translate(
|
return Transform.translate(
|
||||||
offset: Offset(shake, 0),
|
offset: Offset(shake, 0),
|
||||||
child: child,
|
child: child,
|
||||||
|
|||||||
@@ -7,6 +7,7 @@ import '../theme/app_theme.dart';
|
|||||||
/// Shows GPS satellites, LTE signal, Pi temp, voltage, WS status at a glance.
|
/// Shows GPS satellites, LTE signal, Pi temp, voltage, WS status at a glance.
|
||||||
class SystemBar extends StatelessWidget {
|
class SystemBar extends StatelessWidget {
|
||||||
final int? gpsSatellites; // null = disconnected
|
final int? gpsSatellites; // null = disconnected
|
||||||
|
final String? gpsState; // "acquiring", "fix", "lost"
|
||||||
final int? lteSignal; // null = disconnected, 0-4 bars
|
final int? lteSignal; // null = disconnected, 0-4 bars
|
||||||
final double? piTemp; // null = unavailable
|
final double? piTemp; // null = unavailable
|
||||||
final double? voltage; // null = Arduino disconnected
|
final double? voltage; // null = Arduino disconnected
|
||||||
@@ -15,6 +16,7 @@ class SystemBar extends StatelessWidget {
|
|||||||
const SystemBar({
|
const SystemBar({
|
||||||
super.key,
|
super.key,
|
||||||
this.gpsSatellites,
|
this.gpsSatellites,
|
||||||
|
this.gpsState,
|
||||||
this.lteSignal,
|
this.lteSignal,
|
||||||
this.piTemp,
|
this.piTemp,
|
||||||
this.voltage,
|
this.voltage,
|
||||||
@@ -49,14 +51,6 @@ class SystemBar extends StatelessWidget {
|
|||||||
|
|
||||||
return Container(
|
return Container(
|
||||||
padding: const EdgeInsets.symmetric(horizontal: 24),
|
padding: const EdgeInsets.symmetric(horizontal: 24),
|
||||||
decoration: BoxDecoration(
|
|
||||||
border: Border(
|
|
||||||
bottom: BorderSide(
|
|
||||||
color: theme.subdued.withValues(alpha: 0.3),
|
|
||||||
width: 1,
|
|
||||||
),
|
|
||||||
),
|
|
||||||
),
|
|
||||||
child: Row(
|
child: Row(
|
||||||
crossAxisAlignment: CrossAxisAlignment.center,
|
crossAxisAlignment: CrossAxisAlignment.center,
|
||||||
children: [
|
children: [
|
||||||
@@ -73,8 +67,10 @@ class SystemBar extends StatelessWidget {
|
|||||||
),
|
),
|
||||||
_Indicator(
|
_Indicator(
|
||||||
label: 'GPS',
|
label: 'GPS',
|
||||||
value: gpsSatellites?.toString() ?? 'N/A',
|
value: gpsState == 'acquiring' ? 'ACQ'
|
||||||
isAbnormal: gpsSatellites == null || gpsSatellites == 0,
|
: gpsState == 'fix' ? (gpsSatellites?.toString() ?? 'N/A')
|
||||||
|
: '0', // lost or unknown
|
||||||
|
isAbnormal: gpsState != 'fix' || gpsSatellites == null,
|
||||||
alignment: Alignment.centerLeft,
|
alignment: Alignment.centerLeft,
|
||||||
labelSize: labelSize,
|
labelSize: labelSize,
|
||||||
valueSize: valueSize,
|
valueSize: valueSize,
|
||||||
@@ -106,7 +102,7 @@ class SystemBar extends StatelessWidget {
|
|||||||
_Indicator(
|
_Indicator(
|
||||||
label: 'Mains',
|
label: 'Mains',
|
||||||
value: voltage != null ? '${voltage!.toStringAsFixed(1)} V' : 'N/A',
|
value: voltage != null ? '${voltage!.toStringAsFixed(1)} V' : 'N/A',
|
||||||
isAbnormal: voltage == null || voltage! < 11.9,
|
isAbnormal: voltage == null || voltage! < 11.7 || voltage! > 14.5,
|
||||||
alignment: Alignment.centerLeft,
|
alignment: Alignment.centerLeft,
|
||||||
labelSize: labelSize,
|
labelSize: labelSize,
|
||||||
valueSize: valueSize,
|
valueSize: valueSize,
|
||||||
|
|||||||
@@ -64,7 +64,7 @@ class WhiskeyMark extends StatelessWidget {
|
|||||||
Text(
|
Text(
|
||||||
'Roll: ${_formatAngle(roll)}',
|
'Roll: ${_formatAngle(roll)}',
|
||||||
style: TextStyle(
|
style: TextStyle(
|
||||||
fontSize: fontSize * 0.8,
|
fontSize: fontSize * 0.5,
|
||||||
fontWeight: FontWeight.w400,
|
fontWeight: FontWeight.w400,
|
||||||
fontFeatures: const [FontFeature.tabularFigures()],
|
fontFeatures: const [FontFeature.tabularFigures()],
|
||||||
color: theme.foreground,
|
color: theme.foreground,
|
||||||
@@ -72,9 +72,9 @@ class WhiskeyMark extends StatelessWidget {
|
|||||||
),
|
),
|
||||||
SizedBox(width: size * 0.1),
|
SizedBox(width: size * 0.1),
|
||||||
Text(
|
Text(
|
||||||
'P: ${_formatAngle(pitch)}',
|
'Pitch: ${_formatAngle(pitch)}',
|
||||||
style: TextStyle(
|
style: TextStyle(
|
||||||
fontSize: fontSize * 0.8,
|
fontSize: fontSize * 0.5,
|
||||||
fontWeight: FontWeight.w400,
|
fontWeight: FontWeight.w400,
|
||||||
fontFeatures: const [FontFeature.tabularFigures()],
|
fontFeatures: const [FontFeature.tabularFigures()],
|
||||||
color: theme.subdued,
|
color: theme.subdued,
|
||||||
@@ -85,7 +85,7 @@ class WhiskeyMark extends StatelessWidget {
|
|||||||
|
|
||||||
// Label
|
// Label
|
||||||
Text(
|
Text(
|
||||||
'ATTITUDE',
|
'Attitude',
|
||||||
style: TextStyle(
|
style: TextStyle(
|
||||||
fontSize: fontSize * 0.8,
|
fontSize: fontSize * 0.8,
|
||||||
fontWeight: FontWeight.w400,
|
fontWeight: FontWeight.w400,
|
||||||
@@ -101,7 +101,9 @@ class WhiskeyMark extends StatelessWidget {
|
|||||||
|
|
||||||
String _formatAngle(double? angle) {
|
String _formatAngle(double? angle) {
|
||||||
if (angle == null) return '—°';
|
if (angle == null) return '—°';
|
||||||
return '${angle.round()}°';
|
return '${
|
||||||
|
angle.round() > 180 ? angle.round() - 360 : angle.round()
|
||||||
|
}°';
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -178,7 +180,7 @@ class _HorizonPainter extends CustomPainter {
|
|||||||
// Horizon line
|
// Horizon line
|
||||||
final linePaint = Paint()
|
final linePaint = Paint()
|
||||||
..color = lineColor
|
..color = lineColor
|
||||||
..strokeWidth = 2
|
..strokeWidth = borderWeight * 0.1
|
||||||
..style = PaintingStyle.stroke;
|
..style = PaintingStyle.stroke;
|
||||||
|
|
||||||
canvas.drawLine(
|
canvas.drawLine(
|
||||||
@@ -187,12 +189,34 @@ class _HorizonPainter extends CustomPainter {
|
|||||||
linePaint,
|
linePaint,
|
||||||
);
|
);
|
||||||
|
|
||||||
|
// Pitch ladder lines (15° intervals)
|
||||||
|
final ladderPaint = Paint()
|
||||||
|
..color = lineColor
|
||||||
|
..strokeWidth = borderWeight * 0.4
|
||||||
|
..style = PaintingStyle.stroke;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
for (int deg = -75; deg <= 75; deg += 15) {
|
||||||
|
if (deg == 0) continue; // Skip horizon (already drawn)
|
||||||
|
|
||||||
|
final ladderY = horizonY - (deg / 90) * radius;
|
||||||
|
final double widthMod = (100 - (deg < 0 ? -deg : deg)) / 100;
|
||||||
|
final ladderWidth = radius * 0.7 * widthMod; // longer ladder if close to horizon
|
||||||
|
|
||||||
|
canvas.drawLine(
|
||||||
|
Offset(center.dx - ladderWidth, ladderY),
|
||||||
|
Offset(center.dx + ladderWidth, ladderY),
|
||||||
|
ladderPaint,
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
canvas.restore();
|
canvas.restore();
|
||||||
|
|
||||||
// Draw circle border
|
// Draw circle border
|
||||||
final borderPaint = Paint()
|
final borderPaint = Paint()
|
||||||
..color = lineColor.withValues(alpha: 0.5)
|
..color = lineColor
|
||||||
..strokeWidth = borderWeight
|
..strokeWidth = borderWeight * 1.1
|
||||||
..style = PaintingStyle.stroke;
|
..style = PaintingStyle.stroke;
|
||||||
|
|
||||||
canvas.drawCircle(center, radius - 1, borderPaint);
|
canvas.drawCircle(center, radius - 1, borderPaint);
|
||||||
@@ -200,7 +224,7 @@ class _HorizonPainter extends CustomPainter {
|
|||||||
// Draw center reference mark (fixed, doesn't rotate)
|
// Draw center reference mark (fixed, doesn't rotate)
|
||||||
final refPaint = Paint()
|
final refPaint = Paint()
|
||||||
..color = lineColor
|
..color = lineColor
|
||||||
..strokeWidth = borderWeight * 0.8
|
..strokeWidth = borderWeight
|
||||||
..style = PaintingStyle.stroke;
|
..style = PaintingStyle.stroke;
|
||||||
|
|
||||||
// Small wings
|
// Small wings
|
||||||
@@ -214,12 +238,24 @@ class _HorizonPainter extends CustomPainter {
|
|||||||
Offset(center.dx + radius * 0.3, center.dy),
|
Offset(center.dx + radius * 0.3, center.dy),
|
||||||
refPaint,
|
refPaint,
|
||||||
);
|
);
|
||||||
// Center vertical line
|
|
||||||
|
// Center arrow
|
||||||
|
final refTipPaint = Paint()
|
||||||
|
..color = lineColor
|
||||||
|
..strokeWidth = borderWeight * 0.8
|
||||||
|
..style = PaintingStyle.stroke;
|
||||||
|
|
||||||
canvas.drawLine(
|
canvas.drawLine(
|
||||||
Offset(center.dx, center.dy - radius * 0.05),
|
Offset(center.dx, center.dy),
|
||||||
Offset(center.dx, center.dy + radius * 0.1),
|
Offset(center.dx + radius * 0.07, center.dy + radius * 0.1),
|
||||||
refPaint,
|
refTipPaint,
|
||||||
);
|
);
|
||||||
|
canvas.drawLine(
|
||||||
|
Offset(center.dx, center.dy),
|
||||||
|
Offset(center.dx - radius * 0.07, center.dy + radius * 0.1),
|
||||||
|
refTipPaint,
|
||||||
|
);
|
||||||
|
|
||||||
|
|
||||||
canvas.restore();
|
canvas.restore();
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -46,6 +46,8 @@ Called automatically by `build.py`. Looks for theme matching `navigator` in `con
|
|||||||
| `pi_setup_backend.sh` | First-time Pi config for backend (uv, gpsd, systemd) |
|
| `pi_setup_backend.sh` | First-time Pi config for backend (uv, gpsd, systemd) |
|
||||||
| `smartserow-ui.service.sample` | UI systemd unit template |
|
| `smartserow-ui.service.sample` | UI systemd unit template |
|
||||||
| `smartserow-backend.service.sample` | Backend systemd unit template |
|
| `smartserow-backend.service.sample` | Backend systemd unit template |
|
||||||
|
| `smartserow-ui.service` | Production UI systemd unit (gitignored, Pi-specific) |
|
||||||
|
| `smartserow-backend.service` | Production backend systemd unit (gitignored, Pi-specific) |
|
||||||
|
|
||||||
```bash
|
```bash
|
||||||
# On the Pi - UI setup
|
# On the Pi - UI setup
|
||||||
|
|||||||
@@ -78,6 +78,23 @@ def deploy(restart: bool = False) -> bool:
|
|||||||
f"{ssh_target}:{remote_path}/",
|
f"{ssh_target}:{remote_path}/",
|
||||||
])
|
])
|
||||||
|
|
||||||
|
# Ensure system GPIO package is installed (pip version needs compilation)
|
||||||
|
print()
|
||||||
|
print("Ensuring system GPIO package...")
|
||||||
|
run(
|
||||||
|
["ssh", ssh_target, "dpkg -s python3-rpi.gpio >/dev/null 2>&1 || sudo apt install -y python3-rpi.gpio"],
|
||||||
|
check=False,
|
||||||
|
)
|
||||||
|
|
||||||
|
# Create venv with system-site-packages if it doesn't exist
|
||||||
|
# This allows access to apt-installed packages like python3-rpi.gpio
|
||||||
|
print()
|
||||||
|
print("Ensuring venv with system-site-packages...")
|
||||||
|
run(
|
||||||
|
["ssh", ssh_target, f"cd {remote_path} && [ -d .venv ] || ~/.local/bin/uv venv --system-site-packages"],
|
||||||
|
check=False,
|
||||||
|
)
|
||||||
|
|
||||||
# Run uv sync to install/update dependencies
|
# Run uv sync to install/update dependencies
|
||||||
# Use full path since non-interactive SSH doesn't load .bashrc
|
# Use full path since non-interactive SSH doesn't load .bashrc
|
||||||
print()
|
print()
|
||||||
@@ -115,9 +132,10 @@ def deploy(restart: bool = False) -> bool:
|
|||||||
print("Or run this script with --restart flag")
|
print("Or run this script with --restart flag")
|
||||||
|
|
||||||
print()
|
print()
|
||||||
print("Note: First-time setup on Pi requires uv to be installed:")
|
print("Note: First-time setup on Pi requires:")
|
||||||
print(f" ssh {ssh_target}")
|
print(f" ssh {ssh_target}")
|
||||||
print(" curl -LsSf https://astral.sh/uv/install.sh | sh")
|
print(" curl -LsSf https://astral.sh/uv/install.sh | sh # Install uv")
|
||||||
|
print(" sudo apt install python3-rpi.gpio # GPIO support")
|
||||||
|
|
||||||
return True
|
return True
|
||||||
|
|
||||||
|
|||||||
@@ -27,10 +27,10 @@ else
|
|||||||
echo "uv already installed: $(uv --version)"
|
echo "uv already installed: $(uv --version)"
|
||||||
fi
|
fi
|
||||||
|
|
||||||
# Install gpsd
|
# Install gpsd and GPIO support
|
||||||
echo "Installing gpsd..."
|
echo "Installing system packages..."
|
||||||
sudo apt-get update
|
sudo apt-get update
|
||||||
sudo apt-get install -y gpsd gpsd-clients
|
sudo apt-get install -y gpsd gpsd-clients python3-rpi.gpio
|
||||||
|
|
||||||
# Configure gpsd (user needs to edit DEVICES)
|
# Configure gpsd (user needs to edit DEVICES)
|
||||||
GPSD_CONFIG="/etc/default/gpsd"
|
GPSD_CONFIG="/etc/default/gpsd"
|
||||||
@@ -66,7 +66,10 @@ echo ""
|
|||||||
echo "Next steps:"
|
echo "Next steps:"
|
||||||
echo "1. Configure gpsd: sudo nano /etc/default/gpsd"
|
echo "1. Configure gpsd: sudo nano /etc/default/gpsd"
|
||||||
echo "2. Deploy backend: python3 scripts/deploy_backend.py (from dev machine)"
|
echo "2. Deploy backend: python3 scripts/deploy_backend.py (from dev machine)"
|
||||||
echo "3. On Pi, install deps: cd $BACKEND_DIR && uv sync"
|
echo "3. On Pi, create venv and install deps:"
|
||||||
|
echo " cd $BACKEND_DIR"
|
||||||
|
echo " uv venv --system-site-packages # Allows access to apt packages"
|
||||||
|
echo " uv sync"
|
||||||
echo "4. Start service: sudo systemctl start smartserow-backend"
|
echo "4. Start service: sudo systemctl start smartserow-backend"
|
||||||
echo ""
|
echo ""
|
||||||
echo "Useful commands:"
|
echo "Useful commands:"
|
||||||
|
|||||||
Reference in New Issue
Block a user