Skip to content
Draft
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
8 changes: 6 additions & 2 deletions radio/app/controllers/armController.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
from threading import current_thread
from typing import TYPE_CHECKING

from app.signals import DroneError
from app.customTypes import Response
from app.utils import commandAccepted, sendingCommandLock
from pymavlink import mavutil
Expand Down Expand Up @@ -87,8 +88,11 @@ def arm(self, force: bool = False) -> Response:

except Exception as e:
self.drone.logger.error(e, exc_info=True)
if self.drone.droneErrorCb:
self.drone.droneErrorCb(str(e))
self.drone.error(str(e))

## Or you can have just have: (TODO: remove)
DroneError.send(self, msg=str(e))

Comment on lines 89 to +95
Copy link

Copilot AI Apr 8, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This exception path will emit the same error twice: self.drone.error(...) already sends DroneError, then DroneError.send(...) is called again. Please remove the duplicate send (and the TODO comment) so the frontend doesn't receive duplicate drone_error events.

Copilot uses AI. Check for mistakes.
return {
"success": False,
"message": "Could not arm, serial exception",
Expand Down
18 changes: 7 additions & 11 deletions radio/app/drone.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
from app.controllers.serialPortsController import SerialPortsController
from app.controllers.servoController import ServoController
from app.customTypes import Number, Response, VehicleType
from app.signals import DroneError, DroneConnectStatus
from app.utils import (
commandAccepted,
decodeFlightSwVersion,
Expand Down Expand Up @@ -82,7 +83,6 @@ def __init__(
forwarding_address: Optional[str] = None,
droneErrorCb: Optional[Callable] = None,
droneDisconnectCb: Optional[Callable] = None,
droneConnectStatusCb: Optional[Callable] = None,
linkDebugStatsCb: Optional[Callable] = None,
fetchingParameterCb: Optional[Callable] = None,
connectionCancelEvent: Optional[Event] = None,
Expand All @@ -95,7 +95,6 @@ def __init__(
baud (int, optional): The baud rate for the connection. Defaults to 57600.
droneErrorCb (Optional[Callable], optional): Callback function for drone errors. Defaults to None.
droneDisconnectCb (Optional[Callable], optional): Callback function for drone disconnection. Defaults to None.
droneConnectStatusCb (Optional[Callable], optional): Callback function for drone connection providing an update as the drone connects. Defaults to None.
linkDebugStatsCb (Optional[Callable], optional): Callback function for link debug stats. Defaults to None.
fetchingParameterCb (Optional[Callable], optional): Callback function for when parameters are being fetched. Defaults to None.
connectionCancelEvent (Optional[Event], optional): Event to signal if the connection process should be cancelled. Defaults to None.
Expand All @@ -105,7 +104,6 @@ def __init__(
self.logger = logger
self.droneErrorCb = droneErrorCb
self.droneDisconnectCb = droneDisconnectCb
self.droneConnectStatusCb = droneConnectStatusCb
self.linkDebugStatsCb = linkDebugStatsCb
self.fetchingParameterCb = fetchingParameterCb
self.connection_cancel_event: Event = connectionCancelEvent or Event()
Expand Down Expand Up @@ -371,9 +369,6 @@ def setupControllers(self) -> None:
def _emitConnectionStatus(
self, message: str, progress: float, sub_message: str = ""
) -> None:
if not self.droneConnectStatusCb:
return

progress = round(min(max(float(progress), 0.0), 100.0), 2)
progress = max(progress, self._last_connect_progress)
payload = {
Expand All @@ -386,7 +381,7 @@ def _emitConnectionStatus(
return

try:
self.droneConnectStatusCb(payload)
DroneConnectStatus.send(self, msg=payload)
except Exception:
self.logger.exception("Connection status callback failed")
Comment thread
Turnlings marked this conversation as resolved.
return
Expand Down Expand Up @@ -739,8 +734,7 @@ def checkForMessages(self) -> None:
msg = self.master.recv_msg()
except mavutil.mavlink.MAVError as e:
self.logger.error(e, exc_info=True)
if self.droneErrorCb:
self.droneErrorCb(str(e))
self.error(str(e))
continue
except AttributeError as e:
self.logger.error(e, exc_info=True)
Expand All @@ -755,8 +749,7 @@ def checkForMessages(self) -> None:
except Exception as e:
# Log any other unexpected exception
self.logger.error(e, exc_info=True)
if self.droneErrorCb:
self.droneErrorCb(str(e))
self.error(str(e))
continue

if msg is None:
Expand Down Expand Up @@ -1264,6 +1257,9 @@ def stopForwarding(self) -> Response:
else:
return {"success": False, "message": "Not currently forwarding"}

def error(self, msg: str) -> None:
DroneError.send(self, msg=msg)

Comment thread
Turnlings marked this conversation as resolved.
def close(self) -> None:
"""Close the connection to the drone."""
self.logger.info(f"Cleaning up resources for drone at {self}")
Expand Down
2 changes: 0 additions & 2 deletions radio/app/endpoints/autopilot.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@ def rebootAutopilot() -> None:
baud = droneStatus.drone.baud
droneErrorCb = droneStatus.drone.droneErrorCb
droneDisconnectCb = droneStatus.drone.droneDisconnectCb
droneConnectStatusCb = droneStatus.drone.droneConnectStatusCb
linkDebugStatsCb = droneStatus.drone.linkDebugStatsCb
fetchingParameterCb = droneStatus.drone.fetchingParameterCb
forwarding_address = droneStatus.drone.forwarding_address
Expand Down Expand Up @@ -54,7 +53,6 @@ def rebootAutopilot() -> None:
forwarding_address=forwarding_address,
droneErrorCb=droneErrorCb,
droneDisconnectCb=droneDisconnectCb,
droneConnectStatusCb=droneConnectStatusCb,
linkDebugStatsCb=linkDebugStatsCb,
fetchingParameterCb=fetchingParameterCb,
)
Expand Down
2 changes: 0 additions & 2 deletions radio/app/endpoints/comPorts.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@
from app import logger, socketio
from app.drone import Drone
from app.utils import (
droneConnectStatusCb,
droneErrorCb,
fetchingParameterCb,
getComPortNames,
Expand Down Expand Up @@ -157,7 +156,6 @@ def connectToDrone(data: ConnectionDataType) -> None:
forwarding_address=forwarding_address,
droneErrorCb=droneErrorCb,
droneDisconnectCb=disconnectFromDrone,
droneConnectStatusCb=droneConnectStatusCb,
linkDebugStatsCb=sendLinkDebugStats,
fetchingParameterCb=fetchingParameterCb,
connectionCancelEvent=cancel_event,
Expand Down
47 changes: 47 additions & 0 deletions radio/app/signals.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
from blinker import Signal
from . import socketio

from typing import TypedDict, NotRequired
from app.customTypes import Number
Comment on lines +4 to +5
Copy link

Copilot AI Apr 8, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

NotRequired is imported from typing, which will raise ImportError on Python 3.10 (e.g., Ubuntu 22.04 default). Use typing_extensions.NotRequired (and optionally typing_extensions.TypedDict for consistency with the rest of the radio code) or add a version-conditional import fallback.

Copilot uses AI. Check for mistakes.

import logging

logger = logging.getLogger("fgcs")

# Define signals
DroneError = Signal()
DroneConnectStatus = Signal()


@DroneError.connect
def droneErrorHandler(sender, msg: str) -> None:
"""
Send drone error to the socket

Args:
msg: The error message to send to the client
"""
logger.debug(f"dronErrorHandler called by: {sender} with msg: {msg}")
socketio.emit("drone_error", {"message": msg})

Comment thread
Turnlings marked this conversation as resolved.
## Optionally you can add return values
## That would be what the function would return to the caller
# return {success: true}


class DroneConnectionStatusDataType(TypedDict):
message: str
progress: Number
sub_message: NotRequired[str]


@DroneConnectStatus.connect
def droneConnectStatusHandler(sender, msg: DroneConnectionStatusDataType) -> None:
"""
Send drone connect status updates to the socket

Args:
msg: The connect message to send to the client
"""
logger.debug(f"droneConnectStatusHandler called by: {sender} with msg: {msg}")
socketio.emit("drone_connect_status", msg)
19 changes: 1 addition & 18 deletions radio/app/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,8 @@

from pymavlink import mavutil
from serial.tools import list_ports
from typing_extensions import NotRequired, TypedDict

from app.customTypes import Number, VehicleType
from app.customTypes import VehicleType

from . import socketio

Expand Down Expand Up @@ -148,22 +147,6 @@ def droneErrorCb(msg: Any) -> None:
socketio.emit("drone_error", {"message": msg})


class ConnectionDataType(TypedDict):
message: str
progress: Number
sub_message: NotRequired[str]


def droneConnectStatusCb(msg: ConnectionDataType) -> None:
"""
Send drone connect status updates to the socket

Args:
msg: The connect message to send to the client
"""
socketio.emit("drone_connect_status", msg)


def notConnectedError(action: Optional[str] = None) -> None:
"""
Send error to the socket indicating that drone connection must be established to complete this action
Expand Down
2 changes: 2 additions & 0 deletions radio/mypy.ini
Original file line number Diff line number Diff line change
Expand Up @@ -13,3 +13,5 @@ ignore_missing_imports = True
ignore_missing_imports = True
[mypy-docker.*]
ignore_missing_imports = True
[mypy-blinker.*]
ignore_missing_imports = True
Loading