mirror of
https://github.com/azaion/gps-denied-onboard.git
synced 2026-04-22 12:56:36 +00:00
78dcf7b4e7
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>
97 lines
3.1 KiB
Python
97 lines
3.1 KiB
Python
"""FastAPI application factory."""
|
|
|
|
import logging
|
|
from contextlib import asynccontextmanager
|
|
|
|
from fastapi import FastAPI
|
|
|
|
from gps_denied import __version__
|
|
from gps_denied.api.routers import flights
|
|
from gps_denied.config import get_settings
|
|
|
|
logger = logging.getLogger(__name__)
|
|
|
|
|
|
@asynccontextmanager
|
|
async def lifespan(app: FastAPI):
|
|
"""Initialise core pipeline components on startup."""
|
|
from gps_denied.core.chunk_manager import RouteChunkManager
|
|
from gps_denied.core.coordinates import CoordinateTransformer
|
|
from gps_denied.core.gpr import GlobalPlaceRecognition
|
|
from gps_denied.core.graph import FactorGraphOptimizer
|
|
from gps_denied.core.mavlink import MAVLinkBridge
|
|
from gps_denied.core.metric import MetricRefinement
|
|
from gps_denied.core.models import ModelManager
|
|
from gps_denied.core.recovery import FailureRecoveryCoordinator
|
|
from gps_denied.core.rotation import ImageRotationManager
|
|
from gps_denied.core.satellite import SatelliteDataManager
|
|
from gps_denied.core.vo import create_vo_backend
|
|
from gps_denied.schemas.eskf import ESKFConfig
|
|
from gps_denied.schemas.graph import FactorGraphConfig
|
|
|
|
settings = get_settings()
|
|
|
|
mm = ModelManager(engine_dir=str(settings.models.weights_dir))
|
|
vo = create_vo_backend(model_manager=mm)
|
|
gpr = GlobalPlaceRecognition(mm)
|
|
metric = MetricRefinement(mm)
|
|
graph = FactorGraphOptimizer(FactorGraphConfig())
|
|
chunk_mgr = RouteChunkManager(graph)
|
|
recovery = FailureRecoveryCoordinator(chunk_mgr, gpr, metric)
|
|
rotation = ImageRotationManager(mm)
|
|
coord = CoordinateTransformer()
|
|
satellite = SatelliteDataManager(tile_dir=settings.satellite.tile_dir)
|
|
mavlink = MAVLinkBridge(
|
|
connection_string=settings.mavlink.connection,
|
|
output_hz=settings.mavlink.output_hz,
|
|
telemetry_hz=settings.mavlink.telemetry_hz,
|
|
)
|
|
|
|
# ESKF config from env vars (per-airframe tuning)
|
|
eskf_config = ESKFConfig(**settings.eskf.model_dump())
|
|
|
|
# Store on app.state so deps can access them
|
|
app.state.pipeline_components = {
|
|
"vo": vo, "gpr": gpr, "metric": metric,
|
|
"graph": graph, "recovery": recovery,
|
|
"chunk_mgr": chunk_mgr, "rotation": rotation,
|
|
"coord": coord, "satellite": satellite,
|
|
"mavlink": mavlink,
|
|
}
|
|
app.state.eskf_config = eskf_config
|
|
|
|
logger.info(
|
|
"Pipeline ready — MAVLink: %s, tiles: %s",
|
|
settings.mavlink.connection, settings.satellite.tile_dir,
|
|
)
|
|
yield
|
|
|
|
# Cleanup
|
|
try:
|
|
await mavlink.stop()
|
|
except Exception:
|
|
pass
|
|
app.state.pipeline_components = None
|
|
|
|
|
|
def create_app() -> FastAPI:
|
|
"""Factory function to create and configure the FastAPI application."""
|
|
app = FastAPI(
|
|
title="GPS-Denied Onboard API",
|
|
description="REST API for UAV Flight Processing in GPS-denied environments.",
|
|
version=__version__,
|
|
lifespan=lifespan,
|
|
)
|
|
|
|
app.include_router(flights.router)
|
|
|
|
@app.get("/health", tags=["Health"])
|
|
async def health() -> dict[str, str]:
|
|
"""Simple health check endpoint."""
|
|
return {"status": "ok"}
|
|
|
|
return app
|
|
|
|
|
|
app = create_app()
|