mirror of
https://github.com/azaion/gps-denied-onboard.git
synced 2026-04-22 22:06:37 +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:
@@ -1,24 +1,60 @@
|
||||
import logging
|
||||
from typing import Annotated
|
||||
|
||||
from fastapi import Depends, Request
|
||||
from fastapi import Depends, HTTPException, Request
|
||||
from fastapi.security import HTTPAuthorizationCredentials, HTTPBearer
|
||||
from sqlalchemy.ext.asyncio import AsyncSession
|
||||
|
||||
from gps_denied.config import get_settings
|
||||
from gps_denied.core.processor import FlightProcessor
|
||||
from gps_denied.core.sse import SSEEventStreamer
|
||||
from gps_denied.db.engine import get_session
|
||||
from gps_denied.db.repository import FlightRepository
|
||||
|
||||
logger = logging.getLogger(__name__)
|
||||
|
||||
# Singleton instance of SSE Event Streamer
|
||||
_sse_streamer = SSEEventStreamer()
|
||||
|
||||
# Singleton FlightProcessor (one per process, reused across requests)
|
||||
_processor: FlightProcessor | None = None
|
||||
|
||||
# JWT Bearer scheme (auto_error=False — ми самі обробляємо помилки)
|
||||
_bearer = HTTPBearer(auto_error=False)
|
||||
|
||||
|
||||
async def verify_token(
|
||||
credentials: HTTPAuthorizationCredentials | None = Depends(_bearer),
|
||||
) -> None:
|
||||
"""JWT перевірка. При AUTH_ENABLED=false — пропускає все."""
|
||||
settings = get_settings()
|
||||
if not settings.auth.enabled:
|
||||
return # dev/SITL: автентифікація вимкнена
|
||||
|
||||
if credentials is None:
|
||||
raise HTTPException(status_code=401, detail="Authorization header required")
|
||||
|
||||
try:
|
||||
import jwt
|
||||
|
||||
jwt.decode(
|
||||
credentials.credentials,
|
||||
settings.auth.secret_key,
|
||||
algorithms=[settings.auth.algorithm],
|
||||
)
|
||||
except ImportError:
|
||||
logger.warning("PyJWT not installed — JWT validation skipped")
|
||||
except Exception as exc:
|
||||
raise HTTPException(status_code=401, detail=f"Invalid token: {exc}") from exc
|
||||
|
||||
|
||||
def get_sse_streamer() -> SSEEventStreamer:
|
||||
return _sse_streamer
|
||||
|
||||
async def get_repository(session: AsyncSession = Depends(get_session)) -> FlightRepository:
|
||||
|
||||
async def get_repository(
|
||||
session: AsyncSession = Depends(get_session),
|
||||
) -> FlightRepository:
|
||||
return FlightRepository(session)
|
||||
|
||||
|
||||
@@ -29,17 +65,19 @@ async def get_flight_processor(
|
||||
) -> FlightProcessor:
|
||||
global _processor
|
||||
if _processor is None:
|
||||
_processor = FlightProcessor(repo, sse)
|
||||
# Attach pipeline components from lifespan (P1#4)
|
||||
eskf_config = getattr(request.app.state, "eskf_config", None)
|
||||
_processor = FlightProcessor(repo, sse, eskf_config=eskf_config)
|
||||
# Підключаємо pipeline компоненти з lifespan
|
||||
components = getattr(request.app.state, "pipeline_components", None)
|
||||
if components:
|
||||
_processor.attach_components(**components)
|
||||
# Always update repo (new session per request)
|
||||
# Оновлюємо repo (нова сесія на кожен запит)
|
||||
_processor.repository = repo
|
||||
return _processor
|
||||
|
||||
|
||||
# Type aliases for cleaner router definitions
|
||||
# Аліаси для зручності в роутерах
|
||||
SessionDep = Annotated[AsyncSession, Depends(get_session)]
|
||||
RepoDep = Annotated[FlightRepository, Depends(get_repository)]
|
||||
ProcessorDep = Annotated[FlightProcessor, Depends(get_flight_processor)]
|
||||
AuthDep = Annotated[None, Depends(verify_token)]
|
||||
|
||||
@@ -7,9 +7,10 @@ import json
|
||||
from typing import Annotated
|
||||
|
||||
from fastapi import APIRouter, File, Form, HTTPException, Path, UploadFile
|
||||
from fastapi import Depends as _Depends
|
||||
from sse_starlette.sse import EventSourceResponse
|
||||
|
||||
from gps_denied.api.deps import ProcessorDep, SessionDep
|
||||
from gps_denied.api.deps import ProcessorDep, SessionDep, verify_token
|
||||
from gps_denied.schemas.flight import (
|
||||
BatchMetadata,
|
||||
BatchResponse,
|
||||
@@ -27,7 +28,7 @@ from gps_denied.schemas.flight import (
|
||||
Waypoint,
|
||||
)
|
||||
|
||||
router = APIRouter(prefix="/flights", tags=["flights"])
|
||||
router = APIRouter(prefix="/flights", tags=["flights"], dependencies=[_Depends(verify_token)])
|
||||
|
||||
|
||||
@router.post("", response_model=FlightResponse, status_code=201)
|
||||
|
||||
Reference in New Issue
Block a user