Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Flight logs #8

Open
wants to merge 3 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ build/
dist/
doc/build/
doc/skybrush-server-docs-*.zip
flight_logs/
htmlcov/
tmp/
.venv/
Expand Down
2 changes: 1 addition & 1 deletion src/flockwave/server/ext/mavlink/driver.py
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
4 changes: 2 additions & 2 deletions src/flockwave/server/ext/mavlink/log_download.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
13 changes: 8 additions & 5 deletions src/flockwave/server/ext/virtual_uavs/driver.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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

Expand Down
24 changes: 24 additions & 0 deletions src/flockwave/server/model/uav.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
from abc import ABCMeta, abstractproperty
from typing import (
Any,
AsyncIterator,
Callable,
Generic,
Iterable,
Expand All @@ -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
Expand All @@ -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

Expand All @@ -43,6 +47,8 @@
"UAVStatusInfo",
)

FLIGHT_LOGS_DIR = "flight_logs"

log = base_log.getChild("uav")


Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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}.log", "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.

Expand Down