mirror of
https://github.com/azaion/gps-denied-onboard.git
synced 2026-04-23 06:16:38 +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:
@@ -51,6 +51,9 @@ class ESKFConfig(BaseModel):
|
||||
init_accel_bias_var: float = 0.01 # (m/s^2)^2
|
||||
init_gyro_bias_var: float = 1e-6 # (rad/s)^2
|
||||
|
||||
# Mahalanobis outlier rejection (chi-squared threshold for 3-DOF at 5-sigma)
|
||||
mahalanobis_threshold: float = 16.27 # chi2(3, 0.99999) ≈ 5-sigma gate
|
||||
|
||||
|
||||
class ESKFState(BaseModel):
|
||||
"""Full ESKF nominal state snapshot."""
|
||||
|
||||
@@ -28,7 +28,7 @@ class GPSInputMessage(BaseModel):
|
||||
speed_accuracy: float # m/s
|
||||
horiz_accuracy: float # m
|
||||
vert_accuracy: float # m
|
||||
satellites_visible: int = 0
|
||||
satellites_visible: int = 10 # synthetic — prevents ArduPilot satellite-count failsafes
|
||||
|
||||
|
||||
class IMUMessage(BaseModel):
|
||||
|
||||
Reference in New Issue
Block a user