From c5cefe5fc99d442202b2527bbf972daa0ccd9955 Mon Sep 17 00:00:00 2001 From: Thomas Blommaert Date: Sat, 2 Nov 2024 13:31:25 +0100 Subject: [PATCH 1/3] fix: decrease mavlink log burst count for esp8266 --- src/flockwave/server/ext/mavlink/log_download.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/flockwave/server/ext/mavlink/log_download.py b/src/flockwave/server/ext/mavlink/log_download.py index 30769f54..317401c2 100644 --- a/src/flockwave/server/ext/mavlink/log_download.py +++ b/src/flockwave/server/ext/mavlink/log_download.py @@ -137,12 +137,12 @@ async def _get_log_inner( ) -> AsyncIterator[Union[Progress, Optional[FlightLog]]]: last_progress_at = current_time() - # We are requesting at most 512 LOG_DATA messages at once to let the + # We are requesting at most 10 LOG_DATA messages at once to let the # wifi module also take care of other things while doing the download. # Requesting the entire log at once has caused timeout problems with # mavesp8266. The strategy adopted here is identical to what # QGroundControl is doing - MAX_CHUNK_SIZE = 512 * 90 + MAX_CHUNK_SIZE = 10 * 90 try: # Get the size of the log first and create a chunk assembler From b732ac60055b335d504f40d66755cb33b25cf07c Mon Sep 17 00:00:00 2001 From: Thomas Blommaert Date: Sat, 2 Nov 2024 13:31:50 +0100 Subject: [PATCH 2/3] feat: save flight logs to file --- .gitignore | 1 + src/flockwave/server/ext/mavlink/driver.py | 2 +- .../server/ext/virtual_uavs/driver.py | 13 ++++++---- src/flockwave/server/model/uav.py | 24 +++++++++++++++++++ 4 files changed, 34 insertions(+), 6 deletions(-) diff --git a/.gitignore b/.gitignore index 691ae196..98ff6b39 100644 --- a/.gitignore +++ b/.gitignore @@ -11,6 +11,7 @@ build/ dist/ doc/build/ doc/skybrush-server-docs-*.zip +flight_logs/ htmlcov/ tmp/ .venv/ diff --git a/src/flockwave/server/ext/mavlink/driver.py b/src/flockwave/server/ext/mavlink/driver.py index a40c9d16..bda54f41 100644 --- a/src/flockwave/server/ext/mavlink/driver.py +++ b/src/flockwave/server/ext/mavlink/driver.py @@ -704,7 +704,7 @@ async def _enter_low_power_mode_single( ): raise RuntimeError("Failed to request low-power mode from autopilot") - async def get_log( + async def _get_log( self, uav: "MAVLinkUAV", log_id: str ) -> AsyncIterator[Union[Progress, Optional[FlightLog]]]: try: diff --git a/src/flockwave/server/ext/virtual_uavs/driver.py b/src/flockwave/server/ext/virtual_uavs/driver.py index e9999f3a..4458b47e 100644 --- a/src/flockwave/server/ext/virtual_uavs/driver.py +++ b/src/flockwave/server/ext/virtual_uavs/driver.py @@ -10,7 +10,7 @@ from time import monotonic from trio import CancelScope, sleep from trio_util import periodic -from typing import Any, Callable, NoReturn, Optional, Union +from typing import Any, AsyncIterator, Callable, NoReturn, Optional, Union from flockwave.concurrency import delayed from flockwave.ext.manager import ExtensionAPIProxy @@ -1081,11 +1081,14 @@ async def handle_command_yo(self, uav: VirtualUAV) -> str: handle_command_param = create_parameter_command_handler() handle_command_version = create_version_command_handler() - async def get_log(self, uav: VirtualUAV, log_id: str) -> FlightLog: - # Simulate a bit of delay to make it more realistic - await sleep(0.5) + async def _get_log(self, uav: VirtualUAV, log_id: str) -> AsyncIterator[Union[Progress, Optional[FlightLog]]]: + # Simulate some progress to make it more realistic + total_chunks = 10 + for chunk in range(total_chunks): + await sleep(0.2) + yield Progress(percentage=chunk * 100 // total_chunks) try: - return _LOGS[log_id] + yield _LOGS[log_id] except KeyError: raise RuntimeError(f"no such log: {log_id}") from None diff --git a/src/flockwave/server/model/uav.py b/src/flockwave/server/model/uav.py index 137e44a1..55e76076 100644 --- a/src/flockwave/server/model/uav.py +++ b/src/flockwave/server/model/uav.py @@ -5,6 +5,7 @@ from abc import ABCMeta, abstractproperty from typing import ( Any, + AsyncIterator, Callable, Generic, Iterable, @@ -21,6 +22,7 @@ from .attitude import Attitude from .battery import BatteryInfo +from .commands import Progress from .devices import ObjectNode from .gps import GPSFix, GPSFixLike from .log import FlightLog, FlightLogMetadata @@ -31,6 +33,8 @@ from .transport import TransportOptions from .utils import as_base64, scaled_by +import os + if TYPE_CHECKING: from flockwave.server.app import SkybrushServer @@ -43,6 +47,8 @@ "UAVStatusInfo", ) +FLIGHT_LOGS_DIR = "flight_logs" + log = base_log.getChild("uav") @@ -193,6 +199,13 @@ def id(self) -> str: """ return self._id + @property + def padded_id(self) -> str: + """Returns the ID of the UAV, padded with zeros to ensure it has at least + 3 characters. + """ + return self._id.zfill(3) + @property def status(self) -> UAVStatusInfo: """Returns an UAVStatusInfo_ object representing the status of the @@ -489,6 +502,17 @@ def enter_low_power_mode( ) def get_log(self, uav: TUAV, log_id: str) -> FlightLog: + async def wrapper(): + async for result in self._get_log(uav, log_id): + if isinstance(result, FlightLog): + # Write the log to disk + os.makedirs(FLIGHT_LOGS_DIR, exist_ok=True) + with open(f"{FLIGHT_LOGS_DIR}/{uav.padded_id}_{log_id}.txt", "w") as f: + f.write(result.body) + yield result + return wrapper() + + def _get_log(self, uav: TUAV, log_id: str) -> AsyncIterator[Union[Progress, Optional[FlightLog]]]: """Asks the driver to retrieve the log with the given ID from the given UAV. From 704499e1a8ec8155c93aac29e6aa34dc98cafe35 Mon Sep 17 00:00:00 2001 From: Thomas Blommaert Date: Sat, 2 Nov 2024 17:15:27 +0100 Subject: [PATCH 3/3] feat: use .log extension because it is unknown which file format will be downloaded --- src/flockwave/server/model/uav.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/flockwave/server/model/uav.py b/src/flockwave/server/model/uav.py index 55e76076..32e1c35a 100644 --- a/src/flockwave/server/model/uav.py +++ b/src/flockwave/server/model/uav.py @@ -507,7 +507,7 @@ async def wrapper(): if isinstance(result, FlightLog): # Write the log to disk os.makedirs(FLIGHT_LOGS_DIR, exist_ok=True) - with open(f"{FLIGHT_LOGS_DIR}/{uav.padded_id}_{log_id}.txt", "w") as f: + with open(f"{FLIGHT_LOGS_DIR}/{uav.padded_id}_{log_id}.log", "w") as f: f.write(result.body) yield result return wrapper()