px4-configuration 0.1.0__py3-none-any.whl

This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
@@ -0,0 +1,15 @@
1
+ """PX4 Configuration package."""
2
+
3
+ __all__ = ["api"]
4
+
5
+
6
+ def __getattr__(name):
7
+ if name == "__version__":
8
+ from importlib.metadata import version, PackageNotFoundError
9
+
10
+ try:
11
+ return version("px4-configuration")
12
+ except PackageNotFoundError:
13
+ return "0.0.0"
14
+ raise AttributeError(name)
15
+
@@ -0,0 +1,11 @@
1
+ """PX4 Configuration REST API package."""
2
+
3
+ __all__ = [
4
+ "config",
5
+ "models",
6
+ "services",
7
+ "main",
8
+ ]
9
+
10
+ __version__ = "1.0.0"
11
+
@@ -0,0 +1,22 @@
1
+ """Configuration settings for the PX4 Configuration API."""
2
+
3
+ import os
4
+
5
+
6
+ class Settings:
7
+ """Application settings with defaults."""
8
+
9
+ # Default serial connection settings
10
+ default_port: str = os.getenv("PX4_DEFAULT_PORT", "/dev/pixhawk")
11
+ default_baudrate: int = int(os.getenv("PX4_DEFAULT_BAUDRATE", "2000000"))
12
+
13
+ # API settings
14
+ api_title: str = "PX4 Configuration API"
15
+ api_version: str = "1.0.0"
16
+ api_description: str = (
17
+ "REST API for configuring PX4 flight controller from companion computer"
18
+ )
19
+
20
+
21
+ settings = Settings()
22
+
@@ -0,0 +1,262 @@
1
+ """FastAPI application for PX4 configuration API."""
2
+
3
+ from __future__ import annotations
4
+
5
+ import asyncio
6
+ import json
7
+ import os
8
+ import tempfile
9
+ from typing import Optional
10
+
11
+ from fastapi import (
12
+ FastAPI,
13
+ File,
14
+ HTTPException,
15
+ Query,
16
+ UploadFile,
17
+ WebSocket,
18
+ WebSocketDisconnect,
19
+ )
20
+ from fastapi.middleware.cors import CORSMiddleware
21
+ from sse_starlette.sse import EventSourceResponse
22
+
23
+ from .config import settings
24
+ from .models import CalibrationRequest, Px4HealthResponse
25
+ from .services.calibration_service import calibrate_sensors
26
+ from .services.param_service import upload_parameters
27
+ from .services.sdcard_service import upload_to_sdcard
28
+ from .services.shell_service import ShellConnection
29
+ from .services.health_service import read_px4_health
30
+
31
+ app = FastAPI(
32
+ title=settings.api_title,
33
+ version=settings.api_version,
34
+ description=settings.api_description,
35
+ )
36
+
37
+ app.add_middleware(
38
+ CORSMiddleware,
39
+ allow_origins=["*"],
40
+ allow_credentials=True,
41
+ allow_methods=["*"],
42
+ allow_headers=["*"],
43
+ )
44
+
45
+ active_shell_connections: dict[str, ShellConnection] = {}
46
+
47
+
48
+ @app.get("/api/px4/health", response_model=Px4HealthResponse)
49
+ async def get_px4_health(
50
+ port: Optional[str] = Query(None),
51
+ baudrate: Optional[int] = Query(None),
52
+ ):
53
+ """Return a PX4 health snapshot (one-shot JSON)."""
54
+
55
+ port = port or settings.default_port
56
+ baudrate = baudrate or settings.default_baudrate
57
+
58
+ return await read_px4_health(port=port, baudrate=baudrate)
59
+
60
+ @app.post("/api/calibration/start")
61
+ async def start_calibration(request: CalibrationRequest):
62
+ port = request.port or settings.default_port
63
+ baudrate = request.baudrate or settings.default_baudrate
64
+
65
+ async def event_generator():
66
+ try:
67
+ async for payload in calibrate_sensors(
68
+ port=port,
69
+ baudrate=baudrate,
70
+ calibration_type=request.calibration_type, # <-- enum here
71
+ ):
72
+ # Convert dict -> SSE frame
73
+ yield f"data: {json.dumps(payload)}\n\n"
74
+ except Exception as exc:
75
+ yield f"data: {json.dumps({'type': 'error', 'message': str(exc)})}\n\n"
76
+ finally:
77
+ yield f"data: {json.dumps({'type': 'complete'})}\n\n"
78
+
79
+ return EventSourceResponse(event_generator())
80
+
81
+
82
+ @app.post("/api/params/upload")
83
+ async def upload_params(
84
+ file: UploadFile = File(...),
85
+ port: Optional[str] = Query(None, description="Serial port (default: /dev/pixhawk)"),
86
+ baudrate: Optional[int] = Query(None, description="Serial baudrate (default: 2000000)"),
87
+ ):
88
+ """Upload parameters from a `.params` file and stream progress."""
89
+
90
+ port = port or settings.default_port
91
+ baudrate = baudrate or settings.default_baudrate
92
+
93
+ with tempfile.NamedTemporaryFile(mode="w", delete=False, suffix=".params") as tmp_file:
94
+ content = await file.read()
95
+ tmp_file.write(content.decode("utf-8"))
96
+ tmp_file_path = tmp_file.name
97
+
98
+ async def event_generator():
99
+ try:
100
+ async for message in upload_parameters(
101
+ param_file_path=tmp_file_path,
102
+ port=port,
103
+ baudrate=baudrate,
104
+ ):
105
+ yield message
106
+ except Exception as exc: # pragma: no cover
107
+ yield f'data: {json.dumps({"type": "error", "message": str(exc)})}\n\n'
108
+ finally:
109
+ yield f'data: {json.dumps({"type": "complete"})}\n\n'
110
+ try:
111
+ os.unlink(tmp_file_path)
112
+ except OSError:
113
+ pass
114
+
115
+ return EventSourceResponse(event_generator())
116
+
117
+
118
+ @app.post("/api/sdcard/upload")
119
+ async def upload_sdcard_file(
120
+ file: UploadFile = File(...),
121
+ port: Optional[str] = Query(None, description="Serial port (default: /dev/pixhawk)"),
122
+ baudrate: Optional[int] = Query(None, description="Serial baudrate (default: 2000000)"),
123
+ ):
124
+ """Upload a file (e.g. extras.txt) to the PX4 SD card."""
125
+
126
+ port = port or settings.default_port
127
+ baudrate = baudrate or settings.default_baudrate
128
+
129
+ with tempfile.NamedTemporaryFile(mode="w", delete=False) as tmp_file:
130
+ content = await file.read()
131
+ tmp_file.write(content.decode("utf-8"))
132
+ tmp_file_path = tmp_file.name
133
+
134
+ async def event_generator():
135
+ try:
136
+ async for message in upload_to_sdcard(
137
+ file_path=tmp_file_path,
138
+ port=port,
139
+ baudrate=baudrate,
140
+ ):
141
+ yield message
142
+ except Exception as exc: # pragma: no cover
143
+ yield f'data: {json.dumps({"type": "error", "message": str(exc)})}\n\n'
144
+ finally:
145
+ yield f'data: {json.dumps({"type": "complete"})}\n\n'
146
+ try:
147
+ os.unlink(tmp_file_path)
148
+ except OSError:
149
+ pass
150
+
151
+ return EventSourceResponse(event_generator())
152
+
153
+
154
+ @app.websocket("/api/shell/connect")
155
+ async def shell_websocket(
156
+ websocket: WebSocket,
157
+ port: Optional[str] = Query(None, description="Serial port (default: /dev/pixhawk)"),
158
+ baudrate: Optional[int] = Query(None, description="Serial baudrate (default: 2000000)"),
159
+ ):
160
+ """WebSocket endpoint for interactive PX4 shell access."""
161
+
162
+ await websocket.accept()
163
+
164
+ port = port or settings.default_port
165
+ baudrate = baudrate or settings.default_baudrate
166
+
167
+ connection_id = f"{port}:{baudrate}"
168
+ shell_conn = None
169
+
170
+ try:
171
+ shell_conn = ShellConnection(port=port, baudrate=baudrate)
172
+ active_shell_connections[connection_id] = shell_conn
173
+ await shell_conn.connect()
174
+
175
+ await websocket.send_text("Connected to PX4 shell. Type commands and press Enter.\n")
176
+
177
+ async def send_output():
178
+ try:
179
+ while shell_conn.connected:
180
+ output = await shell_conn.receive_output()
181
+ if output:
182
+ await websocket.send_text(output)
183
+ await asyncio.sleep(0.05)
184
+ except asyncio.CancelledError: # pragma: no cover
185
+ pass
186
+ except Exception as exc: # pragma: no cover
187
+ try:
188
+ await websocket.send_text(f"Error receiving output: {exc}\n")
189
+ except Exception:
190
+ pass
191
+
192
+ output_task = asyncio.create_task(send_output())
193
+
194
+ while True:
195
+ try:
196
+ command = await websocket.receive_text()
197
+ if command.strip():
198
+ await shell_conn.send_command(command)
199
+ except WebSocketDisconnect:
200
+ break
201
+ except Exception as exc:
202
+ await websocket.send_text(f"Error: {exc}\n")
203
+
204
+ output_task.cancel()
205
+
206
+ except Exception as exc: # pragma: no cover
207
+ await websocket.send_text(f"Connection error: {exc}\n")
208
+ finally:
209
+ if shell_conn:
210
+ await shell_conn.disconnect()
211
+ if connection_id in active_shell_connections:
212
+ del active_shell_connections[connection_id]
213
+ try:
214
+ await websocket.close()
215
+ except Exception:
216
+ pass
217
+
218
+
219
+ def run(host: str = "0.0.0.0", port: int = 8000, reload: bool = False, log_level: str = "info") -> None:
220
+ """Run the FastAPI application using Uvicorn."""
221
+
222
+ import uvicorn
223
+
224
+ uvicorn.run(
225
+ "px4_configuration.api.main:app",
226
+ host=host,
227
+ port=port,
228
+ reload=reload,
229
+ log_level=log_level,
230
+ )
231
+
232
+
233
+ def main() -> None:
234
+ """Console script entry point for running the API server."""
235
+
236
+ import argparse
237
+
238
+ parser = argparse.ArgumentParser(
239
+ prog="px4-config-api",
240
+ description="Run the PX4 Configuration REST API server",
241
+ )
242
+ parser.add_argument("--host", default="0.0.0.0", help="Bind address (default: 0.0.0.0)")
243
+ parser.add_argument("--port", type=int, default=8000, help="Listen port (default: 8000)")
244
+ parser.add_argument(
245
+ "--reload",
246
+ action="store_true",
247
+ help="Enable auto-reload (development only)",
248
+ )
249
+ parser.add_argument(
250
+ "--log-level",
251
+ default="info",
252
+ choices=["critical", "error", "warning", "info", "debug", "trace"],
253
+ help="Set Uvicorn log level (default: info)",
254
+ )
255
+
256
+ args = parser.parse_args()
257
+ run(host=args.host, port=args.port, reload=args.reload, log_level=args.log_level)
258
+
259
+
260
+ if __name__ == "__main__":
261
+ main()
262
+
@@ -0,0 +1,120 @@
1
+ from __future__ import annotations
2
+
3
+ from enum import StrEnum
4
+ from typing import Literal, Optional, Dict, Any
5
+
6
+ from pydantic import BaseModel, Field, ConfigDict
7
+
8
+
9
+ class CalibrationType(StrEnum):
10
+ """Supported calibration types."""
11
+ GYROSCOPE = "gyroscope"
12
+ ACCELEROMETER = "accelerometer"
13
+ MAGNETOMETER = "magnetometer"
14
+ HORIZON = "horizon"
15
+ ESC = "esc"
16
+
17
+
18
+ class CalibrationRequest(BaseModel):
19
+ """Request model for calibration operations.
20
+
21
+ Exactly one calibration type is selected via `calibration_type`.
22
+ """
23
+
24
+ model_config = ConfigDict(
25
+ json_schema_extra={
26
+ "example": {
27
+ "calibration_type": "accelerometer",
28
+ "port": "/dev/pixhawk",
29
+ "baudrate": 2_000_000,
30
+ }
31
+ }
32
+ )
33
+
34
+ calibration_type: CalibrationType = Field(
35
+ description=(
36
+ "Which calibration to run. "
37
+ "One of: gyroscope, accelerometer, magnetometer, horizon, esc."
38
+ )
39
+ )
40
+ port: str = Field(
41
+ default="/dev/pixhawk",
42
+ description="Serial port device.",
43
+ )
44
+ baudrate: int = Field(
45
+ default=2_000_000,
46
+ description="Serial baudrate (must be positive).",
47
+ ge=1,
48
+ )
49
+
50
+ class CalibrationHealth(BaseModel):
51
+ """Calibration health response."""
52
+
53
+ gyroscope_ok: bool = Field(..., description="Whether the gyroscope is calibrated.")
54
+ accelerometer_ok: bool = Field(..., description="Whether the accelerometer is calibrated.")
55
+ magnetometer_ok: bool = Field(..., description="Whether the magnetometer is calibrated.")
56
+
57
+ @property
58
+ def requires_calibration(self) -> bool:
59
+ """Whether the calibration is required."""
60
+ return not (self.gyroscope_ok and self.accelerometer_ok and self.magnetometer_ok)
61
+
62
+ class Px4HealthResponse(BaseModel):
63
+ """
64
+ High-level PX4 health snapshot.
65
+
66
+ Combines:
67
+ - overall status (ok / degraded / disconnected)
68
+ - connection information
69
+ - calibration health (if available)
70
+ - GPS fix/used satellites
71
+ - armable flag
72
+ - optional raw health flags for debugging/advanced UI
73
+ """
74
+
75
+ status: Literal["ok", "degraded", "disconnected"] = Field(
76
+ ...,
77
+ description="High-level PX4 health status derived from telemetry.",
78
+ )
79
+ connection_port: str = Field(
80
+ ...,
81
+ description="Serial port used to reach the PX4 autopilot.",
82
+ )
83
+ connection_baudrate: int = Field(
84
+ ...,
85
+ description="Baudrate used on the serial link to PX4.",
86
+ )
87
+
88
+ calibration: Optional[CalibrationHealth] = Field(
89
+ default=None,
90
+ description="Sensor calibration health, if telemetry health was received.",
91
+ )
92
+
93
+ gps_fix_type: Optional[str] = Field(
94
+ default=None,
95
+ description=(
96
+ "GPS fix type as a lowercase string (e.g. 'no_fix', '2d_fix', '3d_fix', "
97
+ "'rtk_float', 'rtk_fix'), if GPS info is available."
98
+ ),
99
+ )
100
+ satellites_used: Optional[int] = Field(
101
+ default=None,
102
+ ge=0,
103
+ description=(
104
+ "Number of satellites currently used for the positioning solution, "
105
+ "if GPS info is available."
106
+ ),
107
+ )
108
+
109
+ armable: Optional[bool] = Field(
110
+ default=None,
111
+ description="True if PX4 considers the vehicle armable.",
112
+ )
113
+
114
+ raw_health: Optional[Dict[str, Any]] = Field(
115
+ default=None,
116
+ description=(
117
+ "Optional low-level health flags directly from MAVSDK telemetry.health(), "
118
+ "for debugging or advanced UI use."
119
+ ),
120
+ )
@@ -0,0 +1,9 @@
1
+ """Service modules for PX4 configuration operations."""
2
+
3
+ __all__ = [
4
+ "calibration_service",
5
+ "param_service",
6
+ "sdcard_service",
7
+ "shell_service",
8
+ ]
9
+
@@ -0,0 +1,136 @@
1
+ """Service for PX4 sensor calibration operations."""
2
+
3
+ from __future__ import annotations
4
+
5
+ from typing import AsyncGenerator, Dict, Any
6
+
7
+ from mavsdk import System
8
+
9
+ from ..models import CalibrationType
10
+ from ..utils.calibration_parser import (
11
+ parse_accelerometer_progress,
12
+ parse_gyroscope_progress,
13
+ parse_magnetometer_progress,
14
+ parse_horizon_progress,
15
+ )
16
+
17
+
18
+ async def calibrate_sensors(
19
+ port: str,
20
+ baudrate: int,
21
+ calibration_type: CalibrationType,
22
+ ) -> AsyncGenerator[Dict[str, Any], None]:
23
+ """
24
+ Calibrate PX4 sensors and stream progress as structured dict payloads.
25
+
26
+ This function is transport-agnostic: it does NOT produce SSE-formatted strings.
27
+ It yields plain Python dicts suitable for JSON serialization. The API layer
28
+ (FastAPI endpoint) is responsible for converting these dicts into SSE frames.
29
+ """
30
+
31
+ serial = f"serial://{port}:{baudrate}"
32
+ drone = System()
33
+
34
+ # Initial status messages
35
+ yield {
36
+ "type": "status",
37
+ "message": f"Connecting to {port}...",
38
+ }
39
+
40
+ # Connect to the PX4 system
41
+ await drone.connect(system_address=serial)
42
+
43
+ yield {
44
+ "type": "status",
45
+ "message": "Connected to device",
46
+ }
47
+
48
+ # Dispatch based on calibration type
49
+ if calibration_type is CalibrationType.GYROSCOPE:
50
+ # Gyroscope calibration
51
+ yield {
52
+ "type": "status",
53
+ "message": "Starting gyroscope calibration...",
54
+ }
55
+
56
+ async for progress_data in drone.calibration.calibrate_gyro():
57
+ structured_data = parse_gyroscope_progress(progress_data)
58
+ yield structured_data
59
+
60
+ yield {
61
+ "type": "gyroscope_complete",
62
+ "message": "Gyroscope calibration finished",
63
+ "is_complete": True,
64
+ }
65
+
66
+ elif calibration_type is CalibrationType.ACCELEROMETER:
67
+ # Accelerometer calibration
68
+ yield {
69
+ "type": "status",
70
+ "message": "Starting accelerometer calibration...",
71
+ }
72
+
73
+ async for progress_data in drone.calibration.calibrate_accelerometer():
74
+ structured_data = parse_accelerometer_progress(progress_data)
75
+ yield structured_data
76
+
77
+ yield {
78
+ "type": "accelerometer_complete",
79
+ "message": "Accelerometer calibration finished",
80
+ "is_complete": True,
81
+ }
82
+
83
+ elif calibration_type is CalibrationType.MAGNETOMETER:
84
+ # Magnetometer calibration
85
+ yield {
86
+ "type": "status",
87
+ "message": "Starting magnetometer calibration...",
88
+ }
89
+
90
+ async for progress_data in drone.calibration.calibrate_magnetometer():
91
+ structured_data = parse_magnetometer_progress(progress_data)
92
+ yield structured_data
93
+
94
+ yield {
95
+ "type": "magnetometer_complete",
96
+ "message": "Magnetometer calibration finished",
97
+ "is_complete": True,
98
+ }
99
+
100
+ elif calibration_type is CalibrationType.HORIZON:
101
+ # Level horizon calibration
102
+ yield {
103
+ "type": "status",
104
+ "message": "Starting board level horizon calibration...",
105
+ }
106
+
107
+ async for progress_data in drone.calibration.calibrate_level_horizon():
108
+ structured_data = parse_horizon_progress(progress_data)
109
+ yield structured_data
110
+
111
+ yield {
112
+ "type": "horizon_complete",
113
+ "message": "Level horizon calibration finished",
114
+ "is_complete": True,
115
+ }
116
+
117
+ elif calibration_type is CalibrationType.ESC:
118
+ # ESC calibration not implemented yet
119
+ yield {
120
+ "type": "status",
121
+ "message": "Starting ESC calibration...",
122
+ }
123
+ yield {
124
+ "type": "warning",
125
+ "message": "ESC calibration not yet implemented",
126
+ }
127
+ yield {
128
+ "type": "status",
129
+ "message": "ESC calibration finished",
130
+ }
131
+
132
+ # Final success message for the whole calibration run
133
+ yield {
134
+ "type": "success",
135
+ "message": "Calibration sequence completed",
136
+ }