mirror of
https://github.com/azaion/gps-denied-onboard.git
synced 2026-04-22 23:56:36 +00:00
fix: post-audit — runtime bugs, functional gaps, docs, hardening
Phase A — Runtime bugs: - SSE: add push_event() method to SSEEventStreamer (was missing, masked by mocks) - MAVLink: satellites_visible=10 (was 0, triggers ArduPilot failsafe) - MAVLink: horiz_accuracy=sqrt(P[0,0]+P[1,1]) per spec (was sqrt(avg)) - MAVLink: MEDIUM confidence → fix_type=3 per solution.md (was 2) Phase B — Functional gaps: - handle_user_fix() injects operator GPS into ESKF with noise=500m - app.py uses create_vo_backend() factory (was hardcoded SequentialVO) - ESKF: Mahalanobis gating on satellite updates (rejects outliers >5σ) - ESKF: public accessors (position, quaternion, covariance, last_timestamp) - Processor: no more private ESKF field access Phase C — Documentation: - README: correct API endpoints, CLI command, 40+ env vars documented - Dockerfile: ENV prefixes match pydantic-settings (DB_, SATELLITE_, MAVLINK_) - tech_stack.md marked ARCHIVED (contradicts solution.md) Phase D — Hardening: - JWT auth middleware (AUTH_ENABLED=false default, verify_token on /flights) - TLS config env vars (AUTH_SSL_CERTFILE, AUTH_SSL_KEYFILE) - SHA-256 tile manifest verification in SatelliteDataManager - AuthConfig, ESKFSettings, MAVLinkConfig, SatelliteConfig in config.py Also: conftest.py shared fixtures, download_tiles.py, convert_to_trt.py scripts, config wiring into app.py lifespan, config-driven ESKF, calculate_precise_angle fix. Tests: 196 passed / 8 skipped. Ruff clean. Co-Authored-By: Claude Opus 4.6 (1M context) <noreply@anthropic.com>
This commit is contained in:
@@ -77,8 +77,8 @@ pip install -e ".[dev]"
|
||||
### Запуск
|
||||
|
||||
```bash
|
||||
# Пряме запуск
|
||||
python -m gps_denied
|
||||
# Прямий запуск
|
||||
uvicorn gps_denied.app:app --host 0.0.0.0 --port 8000
|
||||
|
||||
# Docker
|
||||
docker compose up --build
|
||||
@@ -89,12 +89,28 @@ docker compose up --build
|
||||
### Змінні середовища
|
||||
|
||||
```env
|
||||
GPS_DENIED_DB_PATH=/data/flights.db
|
||||
GPS_DENIED_TILE_DIR=/data/satellite_tiles # локальні тайли z/x/y.png
|
||||
GPS_DENIED_LOG_LEVEL=INFO
|
||||
MAVLINK_CONNECTION=serial:/dev/ttyTHS1:57600 # UART на Jetson
|
||||
# Основні
|
||||
DB_URL=sqlite+aiosqlite:///./flight_data.db
|
||||
SATELLITE_TILE_DIR=.satellite_tiles
|
||||
MAVLINK_CONNECTION=serial:/dev/ttyTHS1:57600 # або tcp:host:port
|
||||
MAVLINK_OUTPUT_HZ=5.0
|
||||
MAVLINK_TELEMETRY_HZ=1.0
|
||||
|
||||
# ESKF тюнінг (опціонально)
|
||||
ESKF_VO_POSITION_NOISE=0.3
|
||||
ESKF_SATELLITE_MAX_AGE=30.0
|
||||
ESKF_MAHALANOBIS_THRESHOLD=16.27
|
||||
|
||||
# API
|
||||
API_HOST=127.0.0.1
|
||||
API_PORT=8000
|
||||
|
||||
# Моделі
|
||||
MODEL_WEIGHTS_DIR=weights
|
||||
```
|
||||
|
||||
Повний список: `src/gps_denied/config.py` (40+ параметрів з prefix `DB_`, `API_`, `TILES_`, `MODEL_`, `MAVLINK_`, `SATELLITE_`, `ESKF_`, `RECOVERY_`, `ROTATION_`).
|
||||
|
||||
---
|
||||
|
||||
## API
|
||||
@@ -104,12 +120,14 @@ MAVLINK_CONNECTION=serial:/dev/ttyTHS1:57600 # UART на Jetson
|
||||
| `/health` | GET | Health check |
|
||||
| `/flights` | POST | Створити політ |
|
||||
| `/flights/{id}` | GET | Деталі польоту |
|
||||
| `/flights/{id}` | DELETE | Видалити політ |
|
||||
| `/flights/{id}/images/batch` | POST | Батч зображень |
|
||||
| `/flights/{id}/fix` | POST | GPS-якір від оператора |
|
||||
| `/flights/{id}/status` | GET | Статус обробки |
|
||||
| `/flights/{id}/events` | GET | SSE стрім (позиція + confidence) |
|
||||
| `/flights/{id}/object-gps` | POST | Pixel → GPS (ray-ground проекція) |
|
||||
| `/flights/{flight_id}` | DELETE | Видалити політ |
|
||||
| `/flights/{flight_id}/images/batch` | POST | Батч зображень |
|
||||
| `/flights/{flight_id}/user-fix` | POST | GPS-якір від оператора → ESKF update |
|
||||
| `/flights/{flight_id}/status` | GET | Статус обробки |
|
||||
| `/flights/{flight_id}/stream` | GET | SSE стрім (позиція + confidence) |
|
||||
| `/flights/{flight_id}/frames/{frame_id}/object-to-gps` | POST | Pixel → GPS (ray-ground проекція) |
|
||||
| `/flights/{flight_id}/waypoints/{waypoint_id}` | PUT | Оновити waypoint |
|
||||
| `/flights/{flight_id}/waypoints/batch` | PUT | Batch update waypoints |
|
||||
|
||||
---
|
||||
|
||||
|
||||
Reference in New Issue
Block a user