From 7b9c48897d72a0b1d5652a5c8f9b676f71c33569 Mon Sep 17 00:00:00 2001 From: Ryan Turner <100864486+Turnlings@users.noreply.github.com> Date: Wed, 8 Apr 2026 20:27:58 +0100 Subject: [PATCH 1/3] basic blinker implementation for drone error --- radio/app/controllers/armController.py | 8 ++++++-- radio/app/drone.py | 10 ++++++---- radio/app/signals.py | 13 +++++++++++++ 3 files changed, 25 insertions(+), 6 deletions(-) create mode 100644 radio/app/signals.py diff --git a/radio/app/controllers/armController.py b/radio/app/controllers/armController.py index 719207627..a4664bec0 100644 --- a/radio/app/controllers/armController.py +++ b/radio/app/controllers/armController.py @@ -4,6 +4,7 @@ from threading import current_thread from typing import TYPE_CHECKING +from app.signals import drone_error from app.customTypes import Response from app.utils import commandAccepted, sendingCommandLock from pymavlink import mavutil @@ -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: (TODO: remove) + drone_error.send(str(e)) + return { "success": False, "message": "Could not arm, serial exception", diff --git a/radio/app/drone.py b/radio/app/drone.py index ceef355c9..53865ad67 100644 --- a/radio/app/drone.py +++ b/radio/app/drone.py @@ -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 drone_error from app.utils import ( commandAccepted, decodeFlightSwVersion, @@ -739,8 +740,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) @@ -755,8 +755,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: @@ -1264,6 +1263,9 @@ def stopForwarding(self) -> Response: else: return {"success": False, "message": "Not currently forwarding"} + def error(self, msg: str) -> None: + drone_error.send(msg) + def close(self) -> None: """Close the connection to the drone.""" self.logger.info(f"Cleaning up resources for drone at {self}") diff --git a/radio/app/signals.py b/radio/app/signals.py new file mode 100644 index 000000000..7daffb358 --- /dev/null +++ b/radio/app/signals.py @@ -0,0 +1,13 @@ +from blinker import Signal +from . import socketio + +drone_error = Signal() + + +@drone_error.connect +def drone_error_handler(msg: str): + socketio.emit("drone_error", {"message": msg}) + + ## Optionally you can add return values + ## That would be what the function would return to the caller + # return "Received" From b6e94943629b2bcae82170ef53cbfc66642192d3 Mon Sep 17 00:00:00 2001 From: Ryan Turner <100864486+Turnlings@users.noreply.github.com> Date: Wed, 8 Apr 2026 22:37:23 +0100 Subject: [PATCH 2/3] fully replace drone connection status --- radio/app/controllers/armController.py | 6 ++--- radio/app/drone.py | 12 +++------ radio/app/endpoints/autopilot.py | 2 -- radio/app/endpoints/comPorts.py | 2 -- radio/app/signals.py | 34 +++++++++++++++++++++++--- radio/app/utils.py | 19 +------------- 6 files changed, 38 insertions(+), 37 deletions(-) diff --git a/radio/app/controllers/armController.py b/radio/app/controllers/armController.py index a4664bec0..19ed1e783 100644 --- a/radio/app/controllers/armController.py +++ b/radio/app/controllers/armController.py @@ -4,7 +4,7 @@ from threading import current_thread from typing import TYPE_CHECKING -from app.signals import drone_error +from app.signals import DroneError from app.customTypes import Response from app.utils import commandAccepted, sendingCommandLock from pymavlink import mavutil @@ -90,8 +90,8 @@ def arm(self, force: bool = False) -> Response: self.drone.logger.error(e, exc_info=True) self.drone.error(str(e)) - ## Or you can have: (TODO: remove) - drone_error.send(str(e)) + ## Or you can have just have: (TODO: remove) + DroneError.send(str(e)) return { "success": False, diff --git a/radio/app/drone.py b/radio/app/drone.py index 53865ad67..7f20e7b44 100644 --- a/radio/app/drone.py +++ b/radio/app/drone.py @@ -27,7 +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 drone_error +from app.signals import DroneError, DroneConnectStatus from app.utils import ( commandAccepted, decodeFlightSwVersion, @@ -83,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, @@ -96,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. @@ -106,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() @@ -372,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 = { @@ -387,7 +381,7 @@ def _emitConnectionStatus( return try: - self.droneConnectStatusCb(payload) + DroneConnectStatus.send(payload) except Exception: self.logger.exception("Connection status callback failed") return @@ -1264,7 +1258,7 @@ def stopForwarding(self) -> Response: return {"success": False, "message": "Not currently forwarding"} def error(self, msg: str) -> None: - drone_error.send(msg) + DroneError.send(msg) def close(self) -> None: """Close the connection to the drone.""" diff --git a/radio/app/endpoints/autopilot.py b/radio/app/endpoints/autopilot.py index 5ae2e8f5e..b15390488 100644 --- a/radio/app/endpoints/autopilot.py +++ b/radio/app/endpoints/autopilot.py @@ -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 @@ -54,7 +53,6 @@ def rebootAutopilot() -> None: forwarding_address=forwarding_address, droneErrorCb=droneErrorCb, droneDisconnectCb=droneDisconnectCb, - droneConnectStatusCb=droneConnectStatusCb, linkDebugStatsCb=linkDebugStatsCb, fetchingParameterCb=fetchingParameterCb, ) diff --git a/radio/app/endpoints/comPorts.py b/radio/app/endpoints/comPorts.py index 348f151e7..2a2f4db22 100644 --- a/radio/app/endpoints/comPorts.py +++ b/radio/app/endpoints/comPorts.py @@ -10,7 +10,6 @@ from app import logger, socketio from app.drone import Drone from app.utils import ( - droneConnectStatusCb, droneErrorCb, fetchingParameterCb, getComPortNames, @@ -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, diff --git a/radio/app/signals.py b/radio/app/signals.py index 7daffb358..3b2366255 100644 --- a/radio/app/signals.py +++ b/radio/app/signals.py @@ -1,13 +1,41 @@ from blinker import Signal from . import socketio -drone_error = Signal() +from typing import TypedDict, NotRequired +from app.customTypes import Number +# Define signals +DroneError = Signal() +DroneConnectStatus = Signal() -@drone_error.connect -def drone_error_handler(msg: str): + +@DroneError.connect +def droneErrorHandler(msg: str) -> None: + """ + Send drone error to the socket + + Args: + msg: The error message to send to the client + """ socketio.emit("drone_error", {"message": msg}) ## Optionally you can add return values ## That would be what the function would return to the caller # return "Received" + + +class ConnectionDataType(TypedDict): + message: str + progress: Number + sub_message: NotRequired[str] + + +@DroneConnectStatus.connect +def droneConnectStatusHandler(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) diff --git a/radio/app/utils.py b/radio/app/utils.py index 632f9e9a7..eeb7d908d 100644 --- a/radio/app/utils.py +++ b/radio/app/utils.py @@ -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 @@ -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 From 68c80e73121f4ad5185bac1f9299abb53f488b19 Mon Sep 17 00:00:00 2001 From: Ryan Turner <100864486+Turnlings@users.noreply.github.com> Date: Thu, 9 Apr 2026 23:33:57 +0100 Subject: [PATCH 3/3] include sender in function signature --- radio/app/controllers/armController.py | 2 +- radio/app/drone.py | 4 ++-- radio/app/signals.py | 14 ++++++++++---- radio/mypy.ini | 2 ++ 4 files changed, 15 insertions(+), 7 deletions(-) diff --git a/radio/app/controllers/armController.py b/radio/app/controllers/armController.py index 19ed1e783..b8ee3ac5a 100644 --- a/radio/app/controllers/armController.py +++ b/radio/app/controllers/armController.py @@ -91,7 +91,7 @@ def arm(self, force: bool = False) -> Response: self.drone.error(str(e)) ## Or you can have just have: (TODO: remove) - DroneError.send(str(e)) + DroneError.send(self, msg=str(e)) return { "success": False, diff --git a/radio/app/drone.py b/radio/app/drone.py index 7f20e7b44..674cbec66 100644 --- a/radio/app/drone.py +++ b/radio/app/drone.py @@ -381,7 +381,7 @@ def _emitConnectionStatus( return try: - DroneConnectStatus.send(payload) + DroneConnectStatus.send(self, msg=payload) except Exception: self.logger.exception("Connection status callback failed") return @@ -1258,7 +1258,7 @@ def stopForwarding(self) -> Response: return {"success": False, "message": "Not currently forwarding"} def error(self, msg: str) -> None: - DroneError.send(msg) + DroneError.send(self, msg=msg) def close(self) -> None: """Close the connection to the drone.""" diff --git a/radio/app/signals.py b/radio/app/signals.py index 3b2366255..c262986d0 100644 --- a/radio/app/signals.py +++ b/radio/app/signals.py @@ -4,38 +4,44 @@ from typing import TypedDict, NotRequired from app.customTypes import Number +import logging + +logger = logging.getLogger("fgcs") + # Define signals DroneError = Signal() DroneConnectStatus = Signal() @DroneError.connect -def droneErrorHandler(msg: str) -> None: +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}) ## Optionally you can add return values ## That would be what the function would return to the caller - # return "Received" + # return {success: true} -class ConnectionDataType(TypedDict): +class DroneConnectionStatusDataType(TypedDict): message: str progress: Number sub_message: NotRequired[str] @DroneConnectStatus.connect -def droneConnectStatusHandler(msg: ConnectionDataType) -> None: +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) diff --git a/radio/mypy.ini b/radio/mypy.ini index b99ebf7e3..61b428450 100644 --- a/radio/mypy.ini +++ b/radio/mypy.ini @@ -13,3 +13,5 @@ ignore_missing_imports = True ignore_missing_imports = True [mypy-docker.*] ignore_missing_imports = True +[mypy-blinker.*] +ignore_missing_imports = True