From 1cdd4bafb20ad94582890e8ecb54d3688267972d Mon Sep 17 00:00:00 2001 From: Ben Gilbert Date: Fri, 27 Feb 2026 02:00:31 +0000 Subject: [PATCH 01/17] refactor aircraft type literal to dedicated enum - see commit description this isn't how enum's are supposed to be used in the first place (consistently using `.value`) but this makes the codebase clearer at least until a proper refactor can take place --- radio/app/controllers/flightModesController.py | 6 +++--- radio/app/controllers/frameController.py | 4 ++-- radio/app/controllers/navController.py | 6 +++--- radio/tests/conftest.py | 5 +++-- 4 files changed, 11 insertions(+), 10 deletions(-) diff --git a/radio/app/controllers/flightModesController.py b/radio/app/controllers/flightModesController.py index b82136396..4f750fe3e 100644 --- a/radio/app/controllers/flightModesController.py +++ b/radio/app/controllers/flightModesController.py @@ -5,7 +5,7 @@ from typing import TYPE_CHECKING, List, Union import serial -from app.customTypes import Number, Response +from app.customTypes import Number, Response, VehicleType from app.utils import commandAccepted, sendingCommandLock from pymavlink import mavutil @@ -95,7 +95,7 @@ def setFlightMode(self, mode_number: int, flight_mode: int) -> Response: "message": f"Invalid flight mode number, must be between 1 and 6 inclusive, got {mode_number}.", } - if self.drone.aircraft_type == 1: + if self.drone.aircraft_type == VehicleType.FIXED_WING.value: if (flight_mode < 0) or (flight_mode > 24): return { "success": False, @@ -225,7 +225,7 @@ def setGuidedMode(self) -> Response: mode = mavutil.mavlink.COPTER_MODE_GUIDED - if self.drone.aircraft_type == 1: + if self.drone.aircraft_type == VehicleType.FIXED_WING.value: mode = mavutil.mavlink.PLANE_MODE_GUIDED return self.setCurrentFlightMode(mode) diff --git a/radio/app/controllers/frameController.py b/radio/app/controllers/frameController.py index 181d36351..a660b773e 100644 --- a/radio/app/controllers/frameController.py +++ b/radio/app/controllers/frameController.py @@ -2,7 +2,7 @@ from typing import TYPE_CHECKING, Union -from app.customTypes import Number +from app.customTypes import Number, VehicleType if TYPE_CHECKING: from app.drone import Drone @@ -21,7 +21,7 @@ def __init__(self, drone: Drone) -> None: self.frame_class: Number = 0 # Plane type doesn't have a frame type or class - if self.drone.aircraft_type != 1: + if self.drone.aircraft_type != VehicleType.FIXED_WING.value: self.getFrameType() self.getFrameClass() diff --git a/radio/app/controllers/navController.py b/radio/app/controllers/navController.py index 1158aa0a7..66c66cee2 100644 --- a/radio/app/controllers/navController.py +++ b/radio/app/controllers/navController.py @@ -5,7 +5,7 @@ from typing import TYPE_CHECKING import serial -from app.customTypes import Response +from app.customTypes import Response, VehicleType from app.utils import commandAccepted, sendingCommandLock from pymavlink import mavutil @@ -27,7 +27,7 @@ def __init__(self, drone: Drone) -> None: self.loiter_radius_param_type = mavutil.mavlink.MAV_PARAM_TYPE_INT16 self.loiter_radius = 80.0 # Default loiter radius if ( - self.drone.aircraft_type == 1 + self.drone.aircraft_type == VehicleType.FIXED_WING.value ): # Copter doesn't have loiter radius, only Plane self.getLoiterRadiusFromDrone() @@ -263,7 +263,7 @@ def reposition(self, lat: float, lon: float, alt: float) -> Response: try: # drone.aircraft_type == 1 for fixed wing. Check customTypes.py - if self.drone.aircraft_type == 1: + if self.drone.aircraft_type == VehicleType.FIXED_WING.value: with self.drone.sending_command_lock: # https://mavlink.io/en/messages/common.html#MISSION_ITEM_INT # https://ardupilot.org/dev/docs/plane-commands-in-guided-mode.html diff --git a/radio/tests/conftest.py b/radio/tests/conftest.py index 467f7bf96..eadcb8c08 100644 --- a/radio/tests/conftest.py +++ b/radio/tests/conftest.py @@ -2,6 +2,7 @@ import pytest from app.drone import Drone from app.utils import getComPort +from app.customTypes import VehicleType def pytest_configure(config): @@ -72,9 +73,9 @@ def check_aircraft_type(request): aircraft_type = droneStatus.drone.aircraft_type # Skip if marked as plane_only but not a plane - if "plane_only" in markers and aircraft_type != 1: + if "plane_only" in markers and aircraft_type != VehicleType.FIXED_WING.value: pytest.skip(f"Test requires plane SITL (current type: {aircraft_type})") # Skip if marked as copter_only but not a copter - if "copter_only" in markers and aircraft_type != 2: + if "copter_only" in markers and aircraft_type != VehicleType.MULTIROTOR.value: pytest.skip(f"Test requires copter SITL (current type: {aircraft_type})") From e6cf58edebb2a48271a3c64a1db485c0d5888538 Mon Sep 17 00:00:00 2001 From: Ben Gilbert Date: Fri, 27 Feb 2026 07:17:14 +0000 Subject: [PATCH 02/17] failsafes --- gcs/src/components/config/failsafe.jsx | 392 +++++++++++++++++++ gcs/src/config.jsx | 7 + gcs/src/redux/middleware/emitters.js | 19 + gcs/src/redux/middleware/socketMiddleware.js | 26 ++ gcs/src/redux/slices/configSlice.js | 27 ++ radio/app/endpoints/__init__.py | 1 + radio/app/endpoints/failsafe.py | 125 ++++++ 7 files changed, 597 insertions(+) create mode 100644 gcs/src/components/config/failsafe.jsx create mode 100644 radio/app/endpoints/failsafe.py diff --git a/gcs/src/components/config/failsafe.jsx b/gcs/src/components/config/failsafe.jsx new file mode 100644 index 000000000..fe15639c6 --- /dev/null +++ b/gcs/src/components/config/failsafe.jsx @@ -0,0 +1,392 @@ +import { useEffect } from "react" + +import { LoadingOverlay, NumberInput, Select, Switch } from "@mantine/core" + +import { useDispatch, useSelector } from "react-redux" + +import apmParamDefsCopter from "../../../data/gen_apm_params_def_copter.json" +import apmParamDefsPlane from "../../../data/gen_apm_params_def_plane.json" + +import { + emitGetFailsafeConfig, + emitSetFailsafeConfigParam, + selectFailsafeConfig, + selectRefreshingFailsafeConfigData, +} from "../../redux/slices/configSlice" +import { + emitSetState, + selectConnectedToDrone, +} from "../../redux/slices/droneConnectionSlice" +import { selectAircraftTypeString } from "../../redux/slices/droneInfoSlice" + +export default function Failsafes() { + const dispatch = useDispatch() + const connected = useSelector(selectConnectedToDrone) + const failsafeConfig = useSelector(selectFailsafeConfig) + const aircraftTypeString = useSelector(selectAircraftTypeString) + const refreshingFailsafeConfigData = useSelector( + selectRefreshingFailsafeConfigData, + ) + + const paramDefs = + aircraftTypeString === "Copter" ? apmParamDefsCopter : apmParamDefsPlane + + useEffect(() => { + if (!connected) { + return + } + + dispatch(emitSetState("config")) + dispatch(emitGetFailsafeConfig()) + }, [connected]) + + return ( + <> + +
+
+

+ Battery Failsafe +

+
+ +
+

Low Battery (Stage 1)

+
+ { + dispatch(emitSetFailsafeConfigParam({ + param_id: "BATT_LOW_VOLT", + value: Number(value), + })) + }} + /> + { + dispatch(emitSetFailsafeConfigParam({ + param_id: "BATT_LOW_MAH", + value: Number(value), + })) + }} + /> +
+ ({ + value: `${key}`, + label: `${key}: ${paramDefs.BATT_FS_CRT_ACT.Values[key]}`, + }))} + onChange={(value) => { + dispatch(emitSetFailsafeConfigParam({ + param_id: "BATT_FS_CRT_ACT", + value: Number(value), + })) + }} + /> +
+ +
+
+ + {aircraftTypeString === "Copter" && ( + <> +
+
+

+ Radio Failsafe +

+
+ { + dispatch(emitSetFailsafeConfigParam({ + param_id: "RC_FS_TIMEOUT", + value: Number(value), + })) + }} + /> + ({ + value: `${key}`, + label: `${key}: ${paramDefs.FS_GCS_ENABLE.Values[key]}`, + }))} + onChange={(value) => { + dispatch(emitSetFailsafeConfigParam({ + param_id: "FS_GCS_ENABLE", + value: Number(value), + })) + }} + /> +
+
+
+
+
+

+ EKF Failsafe +

+
+ { + dispatch(emitSetFailsafeConfigParam({ + param_id: "FS_EKF_THRESH", + value: Number(value), + })) + }} + /> + ({ + value: `${key}`, + label: `${key}: ${paramDefs.FS_SHORT_ACTN.Values[key]}`, + }))} + onChange={(value) => { + dispatch(emitSetFailsafeConfigParam({ + param_id: "FS_SHORT_ACTN", + value: Number(value), + })) + }} + /> +
+
+

Long Failsafe

+ { + dispatch(emitSetFailsafeConfigParam({ + param_id: "FS_LONG_TIMEOUT", + value: Number(value), + })) + }} + /> + ({ - value: `${key}`, - label: `${key}: ${paramDefs.FS_THR_ENABLE.Values[key]}`, - }))} + data={Object.keys(paramDefs.FS_THR_ENABLE.Values).map( + (key) => ({ + value: `${key}`, + label: `${key}: ${paramDefs.FS_THR_ENABLE.Values[key]}`, + }), + )} onChange={(value) => { - dispatch(emitSetFailsafeConfigParam({ - param_id: "FS_THR_ENABLE", - value: Number(value), - })) + dispatch( + emitSetFailsafeConfigParam({ + param_id: "FS_THR_ENABLE", + value: Number(value), + }), + ) }} />
@@ -199,25 +219,31 @@ export default function Failsafes() { min={0} value={failsafeConfig.FS_GCS_TIMEOUT} onChange={(value) => { - dispatch(emitSetFailsafeConfigParam({ - param_id: "FS_GCS_TIMEOUT", - value: Number(value), - })) + dispatch( + emitSetFailsafeConfigParam({ + param_id: "FS_GCS_TIMEOUT", + value: Number(value), + }), + ) }} /> ({ - value: `${key}`, - label: `${key}: ${paramDefs.FS_EKF_ACTION.Values[key]}`, - }))} + data={Object.keys(paramDefs.FS_EKF_ACTION.Values).map( + (key) => ({ + value: `${key}`, + label: `${key}: ${paramDefs.FS_EKF_ACTION.Values[key]}`, + }), + )} onChange={(value) => { - dispatch(emitSetFailsafeConfigParam({ - param_id: "FS_EKF_ACTION", - value: Number(value), - })) + dispatch( + emitSetFailsafeConfigParam({ + param_id: "FS_EKF_ACTION", + value: Number(value), + }), + ) }} />
- )} @@ -270,7 +301,6 @@ export default function Failsafes() { RC Failsafe
-

Short Failsafe

{ - dispatch(emitSetFailsafeConfigParam({ - param_id: "FS_SHORT_TIMEOUT", - value: Number(value), - })) + dispatch( + emitSetFailsafeConfigParam({ + param_id: "FS_SHORT_TIMEOUT", + value: Number(value), + }), + ) }} /> ({ - value: `${key}`, - label: `${key}: ${paramDefs.FS_LONG_ACTN.Values[key]}`, - }))} + data={Object.keys(paramDefs.FS_LONG_ACTN.Values).map( + (key) => ({ + value: `${key}`, + label: `${key}: ${paramDefs.FS_LONG_ACTN.Values[key]}`, + }), + )} onChange={(value) => { - dispatch(emitSetFailsafeConfigParam({ - param_id: "FS_LONG_ACTN", - value: Number(value), - })) + dispatch( + emitSetFailsafeConfigParam({ + param_id: "FS_LONG_ACTN", + value: Number(value), + }), + ) }} />
-

- Throttle Failsafe -

+

Throttle Failsafe

{ - dispatch(emitSetFailsafeConfigParam({ - param_id: "THR_FAILSAFE", - value: Number(event.currentTarget.checked), - })) + dispatch( + emitSetFailsafeConfigParam({ + param_id: "THR_FAILSAFE", + value: Number(event.currentTarget.checked), + }), + ) }} />
@@ -354,17 +396,17 @@ export default function Failsafes() { min={925} max={2200} onChange={(value) => { - dispatch(emitSetFailsafeConfigParam({ - param_id: "THR_FS_VALUE", - value: Number(value), - })) + dispatch( + emitSetFailsafeConfigParam({ + param_id: "THR_FS_VALUE", + value: Number(value), + }), + ) }} disabled={!failsafeConfig.THR_FAILSAFE} />
-
-
@@ -376,10 +418,12 @@ export default function Failsafes() { className="mr-4" checked={failsafeConfig.FS_GCS_ENABL} onChange={(event) => { - dispatch(emitSetFailsafeConfigParam({ - param_id: "FS_GCS_ENABL", - value: Number(event.currentTarget.checked), - })) + dispatch( + emitSetFailsafeConfigParam({ + param_id: "FS_GCS_ENABL", + value: Number(event.currentTarget.checked), + }), + ) }} />
From fdfb183a59e540b4aea07625f74bdd3db90e67ae Mon Sep 17 00:00:00 2001 From: Ben Gilbert Date: Fri, 27 Feb 2026 16:22:18 +0000 Subject: [PATCH 04/17] copilot suggestions --- gcs/src/components/config/failsafe.jsx | 18 ++-- radio/app/endpoints/failsafe.py | 26 +++--- radio/tests/test_failsafe.py | 118 +++++++++++++++++++++++++ 3 files changed, 142 insertions(+), 20 deletions(-) create mode 100644 radio/tests/test_failsafe.py diff --git a/gcs/src/components/config/failsafe.jsx b/gcs/src/components/config/failsafe.jsx index 4f958fb95..d853d6bdd 100644 --- a/gcs/src/components/config/failsafe.jsx +++ b/gcs/src/components/config/failsafe.jsx @@ -36,7 +36,7 @@ export default function Failsafes() { return } - dispatch(emitSetState("config")) + dispatch(emitSetState("config.failsafe")) dispatch(emitGetFailsafeConfig()) }, [connected]) @@ -53,7 +53,7 @@ export default function Failsafes() { Battery Failsafe
-
+

Low Battery (Stage 1)

-
+

Critical Battery (Stage 2)

Radio Failsafe -
+
GCS Failsafe -
+
EKF Failsafe -
+
-
+

Short Failsafe

-
+

Long Failsafe

-
+

Throttle Failsafe

None: """ Sends the failsafe config to the frontend, only works when the config page is loaded. """ - if droneStatus.state != "config": + if droneStatus.state != "config.failsafe": socketio.emit( "params_error", { @@ -52,15 +52,17 @@ def getFailsafeConfig() -> None: if not droneStatus.drone: logger.warning("Attempted to get the failsafe config when drone is None.") - droneErrorCb("get the failsafe config") + droneErrorCb( + "You must be connected to the drone to access the failsafe configuration." + ) return - requested_params = FAILSAFE_PARAMS + requested_params = [] if droneStatus.drone.aircraft_type == VehicleType.FIXED_WING.value: - requested_params += PLANE_FS_PARAMS + requested_params = FAILSAFE_PARAMS + PLANE_FS_PARAMS if droneStatus.drone.aircraft_type == VehicleType.MULTIROTOR.value: - requested_params += COPTER_FS_PARAMS + requested_params = FAILSAFE_PARAMS + COPTER_FS_PARAMS failsafe_config = {} for param in requested_params: @@ -83,7 +85,7 @@ def setFailsafeParam(data: SetConfigParam) -> None: """ Sets a failsafe parameter based off data passed in, only works when the config page is loaded. """ - if droneStatus.state != "config": + if droneStatus.state != "config.failsafe": socketio.emit( "params_error", { @@ -95,20 +97,22 @@ def setFailsafeParam(data: SetConfigParam) -> None: if not droneStatus.drone: logger.warning("Attempted to set a failsafe param when drone is None.") - droneErrorCb("set a failsafe param") + droneErrorCb( + "You must be connected to the drone to access the failsafe configuration." + ) return param_id = data.get("param_id", None) value = data.get("value", None) - logger.info(param_id) - logger.info(value) - if param_id is None or value is None: droneErrorCb("Param ID and value must be specified.") return - param_type = failsafe_params.get(param_id, {}).get("param_type", None) + param_type = None + if (response := failsafe_params.get(param_id, {})).get("success", False): + param_type = getattr(response.get("data"), "param_type", None) + success = droneStatus.drone.paramsController.setParam(param_id, value, param_type) if success: result = { diff --git a/radio/tests/test_failsafe.py b/radio/tests/test_failsafe.py new file mode 100644 index 000000000..082155aee --- /dev/null +++ b/radio/tests/test_failsafe.py @@ -0,0 +1,118 @@ +import pytest +from flask_socketio import SocketIOTestClient +from pymavlink import mavutil + +from . import falcon_test +from .helpers import NoDrone, send_and_receive, set_params +from app.customTypes import VehicleType + + +FAILSAFE_TEST_PARAMS = [ + ("BATT_LOW_VOLT", 10.5, mavutil.mavlink.MAV_PARAM_TYPE_REAL32), + ("BATT_LOW_MAH", 1000, mavutil.mavlink.MAV_PARAM_TYPE_REAL32), + ("BATT_FS_LOW_ACT", 1, mavutil.mavlink.MAV_PARAM_TYPE_UINT8), + ("BATT_CRT_VOLT", 9.5, mavutil.mavlink.MAV_PARAM_TYPE_REAL32), + ("BATT_CRT_MAH", 500, mavutil.mavlink.MAV_PARAM_TYPE_REAL32), + ("BATT_FS_CRT_ACT", 2, mavutil.mavlink.MAV_PARAM_TYPE_UINT8), + ("FS_OPTIONS", 0, mavutil.mavlink.MAV_PARAM_TYPE_UINT8), + ("FS_THR_ENABLE", 1, mavutil.mavlink.MAV_PARAM_TYPE_UINT8), +] + + +@pytest.fixture(scope="session", autouse=True) +def setup_failsafe_params(): + """ + Ensure required failsafe parameters exist before tests run. + """ + set_params(FAILSAFE_TEST_PARAMS) + + +@falcon_test(pass_drone_status=True) +def test_getFailsafeConfig(socketio_client: SocketIOTestClient, droneStatus): + # Failure: wrong state + droneStatus.state = "params" + assert send_and_receive("get_failsafe_config") == { + "message": "You must be on the config screen to access the failsafe configuration." + } + + # Failure: no drone connected + droneStatus.state = "config.failsafe" + with NoDrone(): + assert send_and_receive("get_failsafe_config") == { + "message": "You must be connected to the drone to access the failsafe configuration." + } + + # Success: multirotor + droneStatus.state = "config.failsafe" + droneStatus.drone.aircraft_type = VehicleType.MULTIROTOR.value + + result = send_and_receive("get_failsafe_config") + assert "params" in result + assert "BATT_LOW_VOLT" in result["params"] + assert "FS_THR_ENABLE" in result["params"] + + +@falcon_test(pass_drone_status=True) +def test_getFailsafeConfig_fixedWing(socketio_client: SocketIOTestClient, droneStatus): + droneStatus.state = "config.failsafe" + droneStatus.drone.aircraft_type = VehicleType.FIXED_WING.value + + result = send_and_receive("get_failsafe_config") + assert "params" in result + assert "THR_FS_VALUE" in result["params"] + + +@falcon_test(pass_drone_status=True) +def test_setFailsafeParam(socketio_client: SocketIOTestClient, droneStatus): + # Failure: wrong state + droneStatus.state = "params" + assert send_and_receive( + "set_failsafe_config_param", + {"param_id": "BATT_LOW_VOLT", "value": 11.0}, + ) == { + "message": "You must be on the config screen to access the failsafe configuration." + } + + # Failure: no drone connected + droneStatus.state = "config.failsafe" + with NoDrone(): + assert send_and_receive( + "set_failsafe_config_param", + {"param_id": "BATT_LOW_VOLT", "value": 11.0}, + ) == { + "message": "You must be connected to the drone to access the failsafe configuration." + } + + # Failure: missing param_id + assert send_and_receive( + "set_failsafe_config_param", + {"value": 11.0}, + ) == {"message": "Param ID and value must be specified."} + + # Failure: missing value + assert send_and_receive( + "set_failsafe_config_param", + {"param_id": "BATT_LOW_VOLT"}, + ) == {"message": "Param ID and value must be specified."} + + # Success + result = send_and_receive( + "set_failsafe_config_param", + {"param_id": "BATT_LOW_VOLT", "value": 11.0}, + ) + + assert result == { + "success": True, + "message": "Parameter BATT_LOW_VOLT successfully set to 11.0.", + "param_id": "BATT_LOW_VOLT", + "value": 11.0, + } + + # Failure: invalid param + result = send_and_receive( + "set_failsafe_config_param", + {"param_id": "INVALID_PARAM", "value": 1}, + ) + + assert result["success"] is False + assert "Failed to set parameter" in result["message"] From d32cc9355336660fa907a0304ccd8feb9e568552 Mon Sep 17 00:00:00 2001 From: Ben Gilbert Date: Fri, 27 Feb 2026 16:25:52 +0000 Subject: [PATCH 05/17] further copilot changes --- gcs/src/components/config/failsafe.jsx | 2 +- radio/app/endpoints/failsafe.py | 1 - 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/gcs/src/components/config/failsafe.jsx b/gcs/src/components/config/failsafe.jsx index d853d6bdd..043a9b9a8 100644 --- a/gcs/src/components/config/failsafe.jsx +++ b/gcs/src/components/config/failsafe.jsx @@ -38,7 +38,7 @@ export default function Failsafes() { dispatch(emitSetState("config.failsafe")) dispatch(emitGetFailsafeConfig()) - }, [connected]) + }, [connected, dispatch]) return ( <> diff --git a/radio/app/endpoints/failsafe.py b/radio/app/endpoints/failsafe.py index f1e4685d9..b1536bfeb 100644 --- a/radio/app/endpoints/failsafe.py +++ b/radio/app/endpoints/failsafe.py @@ -13,7 +13,6 @@ ] COPTER_FS_PARAMS = [ - "FS_OPTIONS", "FS_THR_ENABLE", "RC_FS_TIMEOUT", "FS_GCS_TIMEOUT", From e1ef7644d03057865861a17e7f566c281f807b4f Mon Sep 17 00:00:00 2001 From: Ben Gilbert Date: Fri, 27 Feb 2026 16:46:19 +0000 Subject: [PATCH 06/17] final copilot suggestions --- gcs/src/components/config/failsafe.jsx | 18 ++++++++++++++++++ radio/app/endpoints/failsafe.py | 2 -- 2 files changed, 18 insertions(+), 2 deletions(-) diff --git a/gcs/src/components/config/failsafe.jsx b/gcs/src/components/config/failsafe.jsx index 043a9b9a8..fd37ea680 100644 --- a/gcs/src/components/config/failsafe.jsx +++ b/gcs/src/components/config/failsafe.jsx @@ -70,6 +70,7 @@ export default function Failsafes() { }), ) }} + disabled={failsafeConfig.BATT_LOW_VOLT == undefined} />
@@ -186,6 +192,7 @@ export default function Failsafes() { }), ) }} + disabled={failsafeConfig.RC_FS_TIMEOUT == undefined} />
@@ -268,6 +278,7 @@ export default function Failsafes() { }), ) }} + disabled={failsafeConfig.FS_EKF_THRESH == undefined} />
@@ -352,6 +366,7 @@ export default function Failsafes() { }), ) }} + disabled={failsafeConfig.FS_LONG_TIMEOUT == undefined} /> ({ - value: `${key}`, - label: `${key}: ${paramDefs.FS_THR_ENABLE.Values[key]}`, - }), - )} - onChange={(value) => { - dispatch( - emitSetFailsafeConfigParam({ - param_id: "FS_THR_ENABLE", - value: Number(value), +
+
+
+

+ Radio Failsafe +

+
+ debouncedUpdate("RC_FS_TIMEOUT", Number(value))} + disabled={failsafeConfig.RC_FS_TIMEOUT == undefined} + /> + ({ - value: `${key}`, - label: `${key}: ${paramDefs.FS_GCS_ENABLE.Values[key]}`, - }), - )} - onChange={(value) => { - dispatch( - emitSetFailsafeConfigParam({ - param_id: "FS_GCS_ENABLE", - value: Number(value), +
+

+ GCS Failsafe +

+
+ debouncedUpdate("FS_GCS_TIMEOUT", Number(value))} + disabled={failsafeConfig.FS_GCS_TIMEOUT == undefined} + /> +
-
+

Short Failsafe

{ - dispatch( - emitSetFailsafeConfigParam({ - param_id: "FS_SHORT_TIMEOUT", - value: Number(value), - }), - ) - }} + onChange={(value) => debouncedUpdate("FS_SHORT_TIMEOUT", Number(value))} disabled={failsafeConfig.FS_SHORT_TIMEOUT == undefined} />
-
+

Throttle Failsafe

{ - dispatch( - emitSetFailsafeConfigParam({ - param_id: "THR_FAILSAFE", - value: Number(event.currentTarget.checked), - }), - ) - }} + onChange={(value) => debouncedUpdate("THR_FAILSAFE", Number(value))} disabled={failsafeConfig.THR_FAILSAFE == undefined} />
{ - dispatch( - emitSetFailsafeConfigParam({ - param_id: "THR_FS_VALUE", - value: Number(value), - }), - ) - }} + onChange={(value) => debouncedUpdate("THR_FS_VALUE", Number(value))} disabled={!failsafeConfig.THR_FAILSAFE} />
@@ -427,18 +376,24 @@ export default function Failsafes() {
-
+

GCS Failsafe

- { + debouncedUpdate("FS_GCS_TIMEOUT", Number(value))} + onChange={(value) => + debouncedUpdate("FS_GCS_TIMEOUT", Number(value)) + } disabled={failsafeConfig.FS_GCS_TIMEOUT == undefined} /> debouncedUpdate("FS_SHORT_TIMEOUT", Number(value))} + onChange={(value) => + debouncedUpdate("FS_SHORT_TIMEOUT", Number(value)) + } disabled={failsafeConfig.FS_SHORT_TIMEOUT == undefined} /> Throttle Failsafe debouncedUpdate("THR_FAILSAFE", Number(value))} + onChange={(value) => + debouncedUpdate("THR_FAILSAFE", Number(value)) + } disabled={failsafeConfig.THR_FAILSAFE == undefined} />
@@ -368,7 +386,9 @@ export default function Failsafes() { suffix="µs" min={925} max={2200} - onChange={(value) => debouncedUpdate("THR_FS_VALUE", Number(value))} + onChange={(value) => + debouncedUpdate("THR_FS_VALUE", Number(value)) + } disabled={!failsafeConfig.THR_FAILSAFE} />
diff --git a/gcs/src/redux/middleware/socketMiddleware.js b/gcs/src/redux/middleware/socketMiddleware.js index 396c9b63f..ab579b609 100644 --- a/gcs/src/redux/middleware/socketMiddleware.js +++ b/gcs/src/redux/middleware/socketMiddleware.js @@ -70,7 +70,7 @@ import { updateChannelsConfigParam, updateFailsafeConfigParam, updateGripperConfigParam, - updateServoConfigParam + updateServoConfigParam, } from "../slices/configSlice.js" import { appendToGpsTrack, From 5ed383ea563807ea2837f9a7485c155ded87c345 Mon Sep 17 00:00:00 2001 From: Ben Gilbert Date: Fri, 13 Mar 2026 20:33:34 +0000 Subject: [PATCH 11/17] marking tests copter/plane only --- radio/tests/test_failsafe.py | 2 ++ radio/tests/test_flightMode.py | 1 + 2 files changed, 3 insertions(+) diff --git a/radio/tests/test_failsafe.py b/radio/tests/test_failsafe.py index c07cc2cba..099e926cd 100644 --- a/radio/tests/test_failsafe.py +++ b/radio/tests/test_failsafe.py @@ -26,6 +26,7 @@ def setup_failsafe_params(): set_params(FAILSAFE_TEST_PARAMS) +@pytest.mark.copter_only @falcon_test(pass_drone_status=True) def test_getFailsafeConfig(socketio_client: SocketIOTestClient, droneStatus): # Failure: wrong state @@ -51,6 +52,7 @@ def test_getFailsafeConfig(socketio_client: SocketIOTestClient, droneStatus): assert "FS_THR_ENABLE" in result["params"] +@pytest.mark.plane_only @falcon_test(pass_drone_status=True) def test_getFailsafeConfig_fixedWing(socketio_client: SocketIOTestClient, droneStatus): droneStatus.state = "config.failsafe" diff --git a/radio/tests/test_flightMode.py b/radio/tests/test_flightMode.py index b5aca84b0..598fe39fd 100644 --- a/radio/tests/test_flightMode.py +++ b/radio/tests/test_flightMode.py @@ -139,6 +139,7 @@ def test_setFlightMode_wrongModeNumber( } +@pytest.mark.copter_only @falcon_test(pass_drone_status=True) def test_setFlightMode_successfullySet( socketio_client: SocketIOTestClient, droneStatus From ec83fec2bd73a607f1e06eb5509f84dbcbe6c115 Mon Sep 17 00:00:00 2001 From: Ben Gilbert Date: Sat, 28 Mar 2026 20:01:22 +0000 Subject: [PATCH 12/17] refactor into controller --- gcs/src/components/config/failsafe.jsx | 4 +- radio/app/controllers/failsafeController.py | 81 +++++++++++++++++++++ radio/app/drone.py | 6 +- radio/app/endpoints/failsafe.py | 53 +------------- 4 files changed, 91 insertions(+), 53 deletions(-) create mode 100644 radio/app/controllers/failsafeController.py diff --git a/gcs/src/components/config/failsafe.jsx b/gcs/src/components/config/failsafe.jsx index 750cc4449..c3836397a 100644 --- a/gcs/src/components/config/failsafe.jsx +++ b/gcs/src/components/config/failsafe.jsx @@ -67,7 +67,7 @@ export default function Failsafes() {
-

Low Battery (Stage 1)

+

Low Battery

-

Critical Battery (Stage 2)

+

Critical Battery

None: + self.drone = drone + + self.params = {} + + self.valid_params = [] + if self.drone.aircraft_type == VehicleType.FIXED_WING.value: + self.valid_params = COMMON_FAILSAFE_PARAMS + PLANE_FS_PARAMS + if self.drone.aircraft_type == VehicleType.MULTIROTOR.value: + self.valid_params = COMMON_FAILSAFE_PARAMS + COPTER_FS_PARAMS + + self.getFailsafeParams() + + def getConfig(self): + config = {} + for param in self.valid_params: + self.params[param] = self.drone.paramsController.getCachedParam(param) + config[param] = self.params[param].get("param_value", "UNKNOWN") + + return config + + def setFailsafeParam(self, param_id: str, value: Number) -> bool: + """ + Sets a failsafe related parameter on the drone. + """ + if param_id not in self.valid_params: + self.drone.logger.error( + f"Parameter {param_id} is not a valid failsafe parameter" + ) + return False + + param_type = self.params.get(param_id, {}).get("param_type", None) + + return self.drone.paramsController.setParam(param_id, value, param_type) + + def getFailsafeParams(self) -> None: + """ + Gets the gripper related parameters from the drone. + """ + self.drone.logger.debug("Fetching gripper parameters") + for param in self.valid_params: + self.params[param] = self.drone.paramsController.getSingleParam(param) diff --git a/radio/app/drone.py b/radio/app/drone.py index 57e6f7e72..67ab6cb01 100644 --- a/radio/app/drone.py +++ b/radio/app/drone.py @@ -18,6 +18,7 @@ from app.controllers.flightModesController import FlightModesController from app.controllers.frameController import FrameController from app.controllers.ftpController import FtpController +from app.controllers.failsafeController import FailsafeController from app.controllers.gripperController import GripperController from app.controllers.missionController import MissionController from app.controllers.motorTestController import MotorTestController @@ -119,7 +120,7 @@ def __init__( "Setting up the Servo Controller", "Setting up the nav controller", "Setting up the FTP controller", - "Connection complete", + "Setting up the failsafe controller" "Connection complete", ] self.logger.debug(f"Trying to setup master with port {port} and baud {baud}") @@ -312,6 +313,9 @@ def setupControllers(self) -> None: self.sendConnectionStatusUpdate(13) self.ftpController = FtpController(self) + self.sendConnectionStatusUpdate(14) + self.failsafeController = FailsafeController(self) + def sendConnectionStatusUpdate(self, msg_index): total_msgs = len(self.connection_phases) if msg_index < 0 or msg_index >= total_msgs: diff --git a/radio/app/endpoints/failsafe.py b/radio/app/endpoints/failsafe.py index f6ea62f98..647c06dd6 100644 --- a/radio/app/endpoints/failsafe.py +++ b/radio/app/endpoints/failsafe.py @@ -1,37 +1,7 @@ import app.droneStatus as droneStatus from app import logger, socketio from app.utils import droneErrorCb -from app.customTypes import SetConfigParam, VehicleType - -FAILSAFE_PARAMS = [ - "BATT_LOW_VOLT", - "BATT_LOW_MAH", - "BATT_FS_LOW_ACT", - "BATT_CRT_VOLT", - "BATT_CRT_MAH", - "BATT_FS_CRT_ACT", -] - -COPTER_FS_PARAMS = [ - "FS_THR_ENABLE", - "RC_FS_TIMEOUT", - "FS_GCS_TIMEOUT", - "FS_GCS_ENABLE", - "FS_EKF_THRESH", - "FS_EKF_ACTION", -] - -PLANE_FS_PARAMS = [ - "THR_FS_VALUE", - "THR_FAILSAFE", - "FS_GCS_ENABL", - "FS_SHORT_ACTN", - "FS_LONG_ACTN", - "FS_SHORT_TIMEOUT", - "FS_LONG_TIMEOUT", -] - -failsafe_params = {} +from app.customTypes import SetConfigParam @socketio.on("get_failsafe_config") @@ -56,20 +26,7 @@ def getFailsafeConfig() -> None: ) return - requested_params = [] - - if droneStatus.drone.aircraft_type == VehicleType.FIXED_WING.value: - requested_params = FAILSAFE_PARAMS + PLANE_FS_PARAMS - if droneStatus.drone.aircraft_type == VehicleType.MULTIROTOR.value: - requested_params = FAILSAFE_PARAMS + COPTER_FS_PARAMS - - failsafe_config = {} - for param in requested_params: - failsafe_params[param] = droneStatus.drone.paramsController.getSingleParam( - param - ) - if failsafe_params[param]["success"]: - failsafe_config[param] = failsafe_params[param]["data"].param_value + failsafe_config = droneStatus.drone.failsafeController.getConfig() socketio.emit( "failsafe_config", @@ -106,11 +63,7 @@ def setFailsafeParam(data: SetConfigParam) -> None: droneErrorCb("Param ID and value must be specified.") return - param_type = None - if (response := failsafe_params.get(param_id, {})).get("success", False): - param_type = getattr(response.get("data"), "param_type", None) - - success = droneStatus.drone.paramsController.setParam(param_id, value, param_type) + success = droneStatus.drone.failsafeController.setFailsafeParam(param_id, value) if success: result = { "success": True, From bec0a230c9268572f812b98289220b77c944ee14 Mon Sep 17 00:00:00 2001 From: Ben Gilbert Date: Sat, 28 Mar 2026 20:42:35 +0000 Subject: [PATCH 13/17] fixes --- gcs/src/components/config/failsafe.jsx | 32 ++++++++++----------- gcs/src/config.jsx | 1 - radio/app/controllers/failsafeController.py | 2 +- 3 files changed, 16 insertions(+), 19 deletions(-) diff --git a/gcs/src/components/config/failsafe.jsx b/gcs/src/components/config/failsafe.jsx index c3836397a..b20b373ce 100644 --- a/gcs/src/components/config/failsafe.jsx +++ b/gcs/src/components/config/failsafe.jsx @@ -5,14 +5,12 @@ import { useDebouncedCallback } from "@mantine/hooks" import { useDispatch, useSelector } from "react-redux" -import apmParamDefsCopter from "../../../data/gen_apm_params_def_copter.json" -import apmParamDefsPlane from "../../../data/gen_apm_params_def_plane.json" +import { useParamDefinitions } from "../../helpers/paramDefinitions" import { emitGetFailsafeConfig, emitSetFailsafeConfigParam, selectFailsafeConfig, - selectRefreshingFailsafeConfigData, } from "../../redux/slices/configSlice" import { emitSetState, @@ -24,21 +22,16 @@ export default function Failsafes() { const dispatch = useDispatch() const connected = useSelector(selectConnectedToDrone) const failsafeConfig = useSelector(selectFailsafeConfig) + const { paramDefs } = useParamDefinitions() const aircraftTypeString = useSelector(selectAircraftTypeString) - const refreshingFailsafeConfigData = useSelector( - selectRefreshingFailsafeConfigData, - ) - - const paramDefs = - aircraftTypeString === "Copter" ? apmParamDefsCopter : apmParamDefsPlane const params = useMemo(() => { - if (!failsafeConfig) { - return [] - } + if (!failsafeConfig) { + return [] + } - return { ...failsafeConfig } - }, [failsafeConfig, aircraftTypeString]) + return paramDefs + }, [failsafeConfig, paramDefs]) const debouncedUpdate = useDebouncedCallback((param_id, value) => { dispatch(emitSetFailsafeConfigParam({ param_id, value })) @@ -53,13 +46,18 @@ export default function Failsafes() { dispatch(emitGetFailsafeConfig()) }, [connected, dispatch]) - return ( + if (Object.keys(paramDefs).length === 0) return (
+
+ ) + + return ( +

@@ -75,7 +73,7 @@ export default function Failsafes() { description="Set to 0 to disable." suffix="V" min={0} - value={params.BATT_LOW_VOLT} + value={failsafeConfig.BATT_LOW_VOLT} onChange={(value) => debouncedUpdate("BATT_LOW_VOLT", Number(value)) } diff --git a/gcs/src/config.jsx b/gcs/src/config.jsx index 0bf760972..a8b200d68 100644 --- a/gcs/src/config.jsx +++ b/gcs/src/config.jsx @@ -17,7 +17,6 @@ import Ftp from "./components/config/ftp" import Gripper from "./components/config/gripper" import Motortestpanel from "./components/config/motorTest" import RadioCalibration from "./components/config/radioCalibration" -import ServoOutput from "./components/config/servoOutput" import Layout from "./components/layout" import NoDroneConnected from "./components/noDroneConnected" diff --git a/radio/app/controllers/failsafeController.py b/radio/app/controllers/failsafeController.py index d4b92fb97..ea1e35f9d 100644 --- a/radio/app/controllers/failsafeController.py +++ b/radio/app/controllers/failsafeController.py @@ -53,7 +53,7 @@ def __init__(self, drone: Drone) -> None: def getConfig(self): config = {} for param in self.valid_params: - self.params[param] = self.drone.paramsController.getCachedParam(param) + self.params[param] = self.drone.paramsController.getSingleParam(param) config[param] = self.params[param].get("param_value", "UNKNOWN") return config From 620bc6856394fd4eb1ad4199da29995ef7e3087c Mon Sep 17 00:00:00 2001 From: Ben Gilbert Date: Sat, 28 Mar 2026 20:44:35 +0000 Subject: [PATCH 14/17] test fixes --- radio/tests/test_failsafe.py | 4 ---- radio/tests/test_flightMode.py | 2 -- 2 files changed, 6 deletions(-) diff --git a/radio/tests/test_failsafe.py b/radio/tests/test_failsafe.py index 099e926cd..20460057d 100644 --- a/radio/tests/test_failsafe.py +++ b/radio/tests/test_failsafe.py @@ -2,7 +2,6 @@ from flask_socketio import SocketIOTestClient from pymavlink import mavutil -from . import falcon_test from .helpers import NoDrone, send_and_receive, set_params from app.customTypes import VehicleType @@ -27,7 +26,6 @@ def setup_failsafe_params(): @pytest.mark.copter_only -@falcon_test(pass_drone_status=True) def test_getFailsafeConfig(socketio_client: SocketIOTestClient, droneStatus): # Failure: wrong state droneStatus.state = "params" @@ -53,7 +51,6 @@ def test_getFailsafeConfig(socketio_client: SocketIOTestClient, droneStatus): @pytest.mark.plane_only -@falcon_test(pass_drone_status=True) def test_getFailsafeConfig_fixedWing(socketio_client: SocketIOTestClient, droneStatus): droneStatus.state = "config.failsafe" droneStatus.drone.aircraft_type = VehicleType.FIXED_WING.value @@ -63,7 +60,6 @@ def test_getFailsafeConfig_fixedWing(socketio_client: SocketIOTestClient, droneS assert "THR_FS_VALUE" in result["params"] -@falcon_test(pass_drone_status=True) def test_setFailsafeParam(socketio_client: SocketIOTestClient, droneStatus): # Failure: wrong state droneStatus.state = "params" diff --git a/radio/tests/test_flightMode.py b/radio/tests/test_flightMode.py index a8aa4601f..1e560e9c0 100644 --- a/radio/tests/test_flightMode.py +++ b/radio/tests/test_flightMode.py @@ -1,5 +1,4 @@ import pytest -from . import falcon_test from flask_socketio.test_client import SocketIOTestClient from pymavlink.mavutil import mavlink @@ -133,7 +132,6 @@ def test_setFlightMode_wrongModeNumber( @pytest.mark.copter_only -@falcon_test(pass_drone_status=True) def test_setFlightMode_successfullySet( socketio_client: SocketIOTestClient, droneStatus ): From f924101ec978825dde05da06458fad24e533746c Mon Sep 17 00:00:00 2001 From: Ben Gilbert Date: Sat, 28 Mar 2026 20:48:05 +0000 Subject: [PATCH 15/17] formatting --- gcs/src/components/config/failsafe.jsx | 29 +++++++++++---------- radio/app/controllers/failsafeController.py | 2 +- 2 files changed, 16 insertions(+), 15 deletions(-) diff --git a/gcs/src/components/config/failsafe.jsx b/gcs/src/components/config/failsafe.jsx index b20b373ce..adcc34772 100644 --- a/gcs/src/components/config/failsafe.jsx +++ b/gcs/src/components/config/failsafe.jsx @@ -26,12 +26,12 @@ export default function Failsafes() { const aircraftTypeString = useSelector(selectAircraftTypeString) const params = useMemo(() => { - if (!failsafeConfig) { - return [] - } + if (!failsafeConfig) { + return [] + } - return paramDefs - }, [failsafeConfig, paramDefs]) + return paramDefs + }, [failsafeConfig, paramDefs]) const debouncedUpdate = useDebouncedCallback((param_id, value) => { dispatch(emitSetFailsafeConfigParam({ param_id, value })) @@ -46,15 +46,16 @@ export default function Failsafes() { dispatch(emitGetFailsafeConfig()) }, [connected, dispatch]) - if (Object.keys(paramDefs).length === 0) return ( -
- -
- ) + if (Object.keys(paramDefs).length === 0) + return ( +
+ +
+ ) return (
diff --git a/radio/app/controllers/failsafeController.py b/radio/app/controllers/failsafeController.py index ea1e35f9d..45423ad85 100644 --- a/radio/app/controllers/failsafeController.py +++ b/radio/app/controllers/failsafeController.py @@ -40,7 +40,7 @@ class FailsafeController: def __init__(self, drone: Drone) -> None: self.drone = drone - self.params = {} + self.params: dict = {} self.valid_params = [] if self.drone.aircraft_type == VehicleType.FIXED_WING.value: From ef4223e4d5c7f38cabd540340084314ce2acc9fb Mon Sep 17 00:00:00 2001 From: Ben Gilbert Date: Sat, 28 Mar 2026 20:50:26 +0000 Subject: [PATCH 16/17] lint --- gcs/src/components/config/failsafe.jsx | 8 -------- 1 file changed, 8 deletions(-) diff --git a/gcs/src/components/config/failsafe.jsx b/gcs/src/components/config/failsafe.jsx index adcc34772..57ac9abed 100644 --- a/gcs/src/components/config/failsafe.jsx +++ b/gcs/src/components/config/failsafe.jsx @@ -25,14 +25,6 @@ export default function Failsafes() { const { paramDefs } = useParamDefinitions() const aircraftTypeString = useSelector(selectAircraftTypeString) - const params = useMemo(() => { - if (!failsafeConfig) { - return [] - } - - return paramDefs - }, [failsafeConfig, paramDefs]) - const debouncedUpdate = useDebouncedCallback((param_id, value) => { dispatch(emitSetFailsafeConfigParam({ param_id, value })) }, 500) From dfd61af4615d45a0cb63ac6f54d8de6836967ecf Mon Sep 17 00:00:00 2001 From: Ben Gilbert Date: Sat, 28 Mar 2026 20:53:28 +0000 Subject: [PATCH 17/17] lint again whoopsie --- gcs/src/components/config/failsafe.jsx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gcs/src/components/config/failsafe.jsx b/gcs/src/components/config/failsafe.jsx index 57ac9abed..105b59676 100644 --- a/gcs/src/components/config/failsafe.jsx +++ b/gcs/src/components/config/failsafe.jsx @@ -1,4 +1,4 @@ -import { useEffect, useMemo } from "react" +import { useEffect } from "react" import { LoadingOverlay, NumberInput, Select, Switch } from "@mantine/core" import { useDebouncedCallback } from "@mantine/hooks"