Skip to content

Commit 4c31782

Browse files
authored
Merge pull request #18 from skybrush-io/feat/show-upload-hash
2 parents 0f22e6e + 7dc47d1 commit 4c31782

File tree

9 files changed

+60
-23
lines changed

9 files changed

+60
-23
lines changed

src/flockwave/server/ext/crazyflie/driver.py

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@
3939
from flockwave.server.model.uav import BatteryInfo, UAVBase, UAVDriver, VersionInfo
4040
from flockwave.server.registries.errors import RegistryFull
4141
from flockwave.server.show import (
42+
ShowSpecification,
4243
TrajectorySpecification,
4344
get_group_index_from_show_specification,
4445
get_home_position_from_show_specification,
@@ -390,14 +391,16 @@ async def handle_command_trick(self, uav: "CrazyflieUAV", *params: str) -> str:
390391
f"hover time = {hover_time} s"
391392
)
392393

393-
async def handle_command___show_upload(self, uav: "CrazyflieUAV", *, show):
394+
async def handle_command___show_upload(
395+
self, uav: "CrazyflieUAV", *, show: ShowSpecification
396+
):
394397
"""Handles a drone show upload request for the given UAV.
395398
396399
This is a temporary solution until we figure out something that is
397400
more sustainable in the long run.
398401
399402
Parameters:
400-
show: the show data
403+
show: the show data for a single UAV
401404
"""
402405
await uav.upload_show(show, remember=True)
403406
if self.preferred_controller is not None:
@@ -1019,7 +1022,9 @@ async def test_component(self, component: str) -> None:
10191022
else:
10201023
raise NotSupportedError
10211024

1022-
async def upload_show(self, show, *, remember: bool = True) -> None:
1025+
async def upload_show(
1026+
self, show: ShowSpecification, *, remember: bool = True
1027+
) -> None:
10231028
home = get_home_position_from_show_specification(show)
10241029
trajectory = get_trajectory_from_show_specification(show)
10251030
group_index = get_group_index_from_show_specification(show)

src/flockwave/server/ext/mavlink/driver.py

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,7 @@
5050
VersionInfo,
5151
)
5252
from flockwave.server.show import (
53+
ShowSpecification,
5354
get_altitude_reference_from_show_specification,
5455
get_coordinate_system_from_show_specification,
5556
get_geofence_configuration_from_show_specification,
@@ -383,14 +384,16 @@ async def handle_command_show(self, uav: "MAVLinkUAV", command: str | None = Non
383384
else:
384385
raise RuntimeError(f"Unknown subcommand: {command!r}")
385386

386-
async def handle_command___show_upload(self, uav: "MAVLinkUAV", *, show):
387+
async def handle_command___show_upload(
388+
self, uav: "MAVLinkUAV", *, show: ShowSpecification
389+
):
387390
"""Handles a drone show upload request for the given UAV.
388391
389392
This is a temporary solution until we figure out something that is
390393
more sustainable in the long run.
391394
392395
Parameters:
393-
show: the show data
396+
show: the show data for a single UAV
394397
"""
395398
try:
396399
await uav.upload_show(show)
@@ -2359,7 +2362,7 @@ async def trigger_camera_shutter(self) -> None:
23592362
if not success:
23602363
raise RuntimeError("Failed to trigger camera shutter")
23612364

2362-
async def upload_show(self, show) -> None:
2365+
async def upload_show(self, show: ShowSpecification) -> None:
23632366
coordinate_system = get_coordinate_system_from_show_specification(show)
23642367
if coordinate_system.type != "nwu":
23652368
raise RuntimeError("Only NWU coordinate systems are supported")

src/flockwave/server/ext/show/logging.py

Lines changed: 9 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -2,11 +2,12 @@
22

33
from logging import Logger
44
from time import monotonic
5-
from typing import Any
5+
from typing import Any, cast
66

77
from flockwave.gps.vectors import FlatEarthToGPSCoordinateTransformation
88

99
from flockwave.server.model import Client, FlockwaveMessage
10+
from flockwave.server.show import ShowSpecification
1011

1112
from .metadata import ShowMetadata
1213

@@ -55,7 +56,6 @@ def __init__(self, log: Logger):
5556
Parameter:
5657
log: logger that the middleware will write to
5758
"""
58-
self._last_show_metadata = None
5959
self._last_show_upload_command_at = monotonic() - 1000
6060
self._log = log
6161

@@ -84,7 +84,7 @@ def __call__(self, message: FlockwaveMessage, sender: Client) -> FlockwaveMessag
8484

8585
return message
8686

87-
def _extract_show(self, message: FlockwaveMessage) -> dict[str, Any] | None:
87+
def _extract_show(self, message: FlockwaveMessage) -> ShowSpecification | None:
8888
"""Checks whether the given message is a show upload and extracts the
8989
show specification out of the message if it is.
9090
"""
@@ -104,20 +104,21 @@ def last_show_metadata(self) -> ShowMetadata | None:
104104
return self._last_show_metadata
105105

106106
@staticmethod
107-
def _get_show_fingerprint(show: dict[str, Any]) -> ShowFingerprint:
107+
def _get_show_fingerprint(show: ShowSpecification) -> ShowFingerprint:
108108
"""Extracts the basic show parameters like the origin and the orientation
109109
from the upload. These are used to decide whether an upload attempt is
110110
probably a continuation of an ongoing sequence of requests from the
111111
client or a completely new one.
112112
"""
113+
show_dict = cast(dict[str, Any], show)
113114
return [
114-
get(show, "mission", "id"),
115-
get(show, "coordinateSystem"),
116-
get(show, "amslReference"),
115+
get(show_dict, "mission", "id"),
116+
get(show_dict, "coordinateSystem"),
117+
get(show_dict, "amslReference"),
117118
]
118119

119120
@staticmethod
120-
def _get_metadata_from_upload_request(show: dict[str, Any]) -> ShowMetadata:
121+
def _get_metadata_from_upload_request(show: ShowSpecification) -> ShowMetadata:
121122
"""Extracts the metadata of the current show being uploaded. This is
122123
returned to consumers of the API of the show extension when the caller
123124
requests the metadata of the last uploaded show.

src/flockwave/server/ext/virtual_uavs/driver.py

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,7 @@
4545
from flockwave.server.model.transport import TransportOptions
4646
from flockwave.server.model.uav import UAVBase, UAVDriver, VersionInfo
4747
from flockwave.server.show import (
48+
ShowSpecification,
4849
TrajectoryPlayer,
4950
TrajectorySpecification,
5051
get_coordinate_system_from_show_specification,
@@ -563,7 +564,7 @@ def handle_mission_upload(self, bundle: MissionItemBundle, format: str) -> None:
563564

564565
self.update_status(mode="mission" if self.has_mission_items else "stab")
565566

566-
def handle_show_upload(self, show) -> None:
567+
def handle_show_upload(self, show: ShowSpecification) -> None:
567568
"""Handles the upload of a full drone show (trajectory + light program).
568569
569570
Parameters:
@@ -1164,14 +1165,16 @@ async def handle_command___mission_upload(
11641165
uav.handle_mission_upload(bundle, format)
11651166
await sleep(0.25 + random() * 0.5)
11661167

1167-
async def handle_command___show_upload(self, uav: VirtualUAV, *, show) -> None:
1168+
async def handle_command___show_upload(
1169+
self, uav: VirtualUAV, *, show: ShowSpecification
1170+
) -> None:
11681171
"""Handles a drone show upload request for the given UAV.
11691172
11701173
This is a temporary solution until we figure out something that is
11711174
more sustainable in the long run.
11721175
11731176
Parameters:
1174-
show: the show data
1177+
show: the show data for a single UAV
11751178
"""
11761179
uav.handle_show_upload(show)
11771180
await sleep(0.25 + random() * 0.5)

src/flockwave/server/model/mission.py

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,9 +8,10 @@
88
from dataclasses import dataclass, field
99
from enum import Enum
1010
from itertools import chain
11-
from typing import Any, TypedDict
11+
from typing import Any, TypedDict, cast
1212

1313
from flockwave.server.show import (
14+
ShowSpecification,
1415
get_flight_area_configuration_from_show_specification,
1516
get_geofence_configuration_from_show_specification,
1617
get_safety_configuration_from_show_specification,
@@ -1222,6 +1223,7 @@ def from_json(cls, obj: MissionItem):
12221223
# we need a "flightArea" and a "coordinateSystem" entry, where the latter
12231224
# can be "geodetic" or a complete JSON representation of a
12241225
# FlatEarthToGPSCoordinateTransformation
1226+
params = cast(ShowSpecification, params)
12251227
flight_area = get_flight_area_configuration_from_show_specification(params)
12261228

12271229
return cls(id=id, participants=participants, flight_area=flight_area)
@@ -1261,6 +1263,7 @@ def from_json(cls, obj: MissionItem):
12611263
# we need a "geofence" and a "coordinateSystem" entry, where the latter
12621264
# can be "geodetic" or a complete JSON representation of a
12631265
# FlatEarthToGPSCoordinateTransformation
1266+
params = cast(ShowSpecification, params)
12641267
geofence = get_geofence_configuration_from_show_specification(params)
12651268

12661269
return cls(id=id, participants=participants, geofence=geofence)

src/flockwave/server/show/flight_area.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
from flockwave.server.utils import optional_float
1818

1919
from .specification import (
20+
ShowSpecification,
2021
get_coordinate_system_from_show_specification,
2122
is_coordinate_system_in_show_specification_geodetic,
2223
)
@@ -25,7 +26,7 @@
2526

2627

2728
def get_flight_area_configuration_from_show_specification(
28-
show: dict,
29+
show: ShowSpecification,
2930
) -> FlightAreaConfigurationRequest:
3031
result = FlightAreaConfigurationRequest()
3132

src/flockwave/server/show/geofence.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
from flockwave.server.utils import optional_float
1919

2020
from .specification import (
21+
ShowSpecification,
2122
get_coordinate_system_from_show_specification,
2223
is_coordinate_system_in_show_specification_geodetic,
2324
)
@@ -26,7 +27,7 @@
2627

2728

2829
def get_geofence_configuration_from_show_specification(
29-
show: dict,
30+
show: ShowSpecification,
3031
) -> GeofenceConfigurationRequest:
3132
result = GeofenceConfigurationRequest()
3233

src/flockwave/server/show/lights.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,10 +4,12 @@
44

55
from base64 import b64decode
66

7+
from .specification import ShowSpecification
8+
79
__all__ = ("get_light_program_from_show_specification",)
810

911

10-
def get_light_program_from_show_specification(show: dict) -> bytes:
12+
def get_light_program_from_show_specification(show: ShowSpecification) -> bytes:
1113
"""Returns the raw Skybrush light program as bytecode from the given
1214
show specification object.
1315
"""

src/flockwave/server/show/specification.py

Lines changed: 20 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,5 @@
1+
from typing import Any, TypedDict
2+
13
from flockwave.gps.vectors import FlatEarthToGPSCoordinateTransformation
24

35
from .trajectory import TrajectorySpecification
@@ -14,8 +16,24 @@
1416
)
1517

1618

17-
ShowSpecification = dict
18-
"""Type alias for show specification objects."""
19+
class ShowSpecification(TypedDict, total=False):
20+
"""Specification of a drone show for a single UAV as it appears
21+
in show upload commands coming from Skybrush Live."""
22+
23+
cues: dict[str, Any]
24+
validation: dict[str, Any]
25+
trajectory: dict[str, Any]
26+
lights: dict[str, Any]
27+
rthPlan: dict[str, Any]
28+
home: list[float]
29+
landAt: list[float]
30+
name: str
31+
amslReference: float
32+
coordinateSystem: dict[str, Any]
33+
geofence: dict[str, Any]
34+
mission: dict[str, Any]
35+
group: int
36+
flightArea: dict[str, Any]
1937

2038

2139
def get_trajectory_from_show_specification(

0 commit comments

Comments
 (0)