From ee3e4ca400f0d0b2dded80d25250c10fa8a3b8a1 Mon Sep 17 00:00:00 2001 From: Kush Makkapati Date: Sat, 13 Dec 2025 14:05:01 +0000 Subject: [PATCH 1/4] Add modal for force disarming if normal disarm fails --- .../components/dashboard/ForceDisarmModal.jsx | 52 +++++++++++++++++++ gcs/src/dashboard.jsx | 12 +++-- gcs/src/redux/middleware/socketMiddleware.js | 12 ++++- gcs/src/redux/slices/droneConnectionSlice.js | 8 +++ radio/app/controllers/armController.py | 4 +- radio/app/endpoints/arm.py | 6 ++- 6 files changed, 85 insertions(+), 9 deletions(-) create mode 100644 gcs/src/components/dashboard/ForceDisarmModal.jsx diff --git a/gcs/src/components/dashboard/ForceDisarmModal.jsx b/gcs/src/components/dashboard/ForceDisarmModal.jsx new file mode 100644 index 000000000..612a6892d --- /dev/null +++ b/gcs/src/components/dashboard/ForceDisarmModal.jsx @@ -0,0 +1,52 @@ +import { Button, Modal, Text } from "@mantine/core" +import { useDispatch, useSelector } from "react-redux" +import { + emitArmDisarm, + selectForceDisarmModalOpened, + setForceDisarmModalOpened, +} from "../../redux/slices/droneConnectionSlice" + +export default function ForceDisarmModal() { + const dispatch = useDispatch() + const isOpen = useSelector(selectForceDisarmModalOpened) + + const handleForceDisarm = () => { + dispatch(emitArmDisarm({ arm: false, force: true })) + dispatch(setForceDisarmModalOpened(false)) + } + + const handleCancel = () => { + dispatch(setForceDisarmModalOpened(false)) + } + + return ( + +
+ + The aircraft failed to disarm normally. This could be because the + aircraft is still in the air or has other safety concerns. + + + Do you want to force disarm the aircraft? + + + Warning: Force disarming bypasses safety checks and could cause the + aircraft to crash if it's still airborne. + +
+ + +
+
+
+ ) +} diff --git a/gcs/src/dashboard.jsx b/gcs/src/dashboard.jsx index 6bd72c6fc..cd18192d9 100644 --- a/gcs/src/dashboard.jsx +++ b/gcs/src/dashboard.jsx @@ -34,21 +34,24 @@ import { selectBatteryData, selectDroneCoords, selectFlightMode, - selectGPSRawInt, selectGPS2RawInt, + selectGPSRawInt, + selectHasSecondaryGps, selectNotificationSound, selectRSSI, soundPlayed, - selectHasSecondaryGps, } from "./redux/slices/droneInfoSlice" -import { selectMessages } from "./redux/slices/statusTextSlice" import { selectCurrentMission } from "./redux/slices/missionSlice" +import { selectMessages } from "./redux/slices/statusTextSlice" import { useSettings } from "./helpers/settings" // Helper javascript files import { GPS_FIX_TYPES } from "./helpers/mavlinkConstants" +// Import components +import ForceDisarmModal from "./components/dashboard/ForceDisarmModal" + // Custom component import useSound from "use-sound" import FloatingToolbar from "./components/dashboard/floatingToolbar" @@ -69,9 +72,9 @@ const tailwindColors = resolveConfig(tailwindConfig).theme.colors // Sounds import armSound from "./assets/sounds/armed.mp3" import disarmSound from "./assets/sounds/disarmed.mp3" +import flightModeChangedSound from "./assets/sounds/flightmodechanged.mp3" import lowBatterySound from "./assets/sounds/lowbattery.mp3" import waypointReachedSound from "./assets/sounds/waypointreached.mp3" -import flightModeChangedSound from "./assets/sounds/flightmodechanged.mp3" export default function Dashboard() { const dispatch = useDispatch() @@ -353,6 +356,7 @@ export default function Dashboard() { + ) } diff --git a/gcs/src/redux/middleware/socketMiddleware.js b/gcs/src/redux/middleware/socketMiddleware.js index bfab1d6d8..fbf49b839 100644 --- a/gcs/src/redux/middleware/socketMiddleware.js +++ b/gcs/src/redux/middleware/socketMiddleware.js @@ -17,6 +17,7 @@ import { setConnectionModal, setConnectionStatus, setFetchingComPorts, + setForceDisarmModalOpened, setSelectedComPorts, } from "../slices/droneConnectionSlice" @@ -60,9 +61,9 @@ import { setEkfStatusReportData, setExtraData, setFlightSwVersion, + setGps2RawIntData, setGpsData, setGpsRawIntData, - setGps2RawIntData, setGuidedModePinData, setHeartbeatData, setHomePosition, @@ -519,7 +520,14 @@ const socketMiddleware = (store) => { }) socket.socket.on(DroneSpecificSocketEvents.onArmDisarm, (msg) => { - if (!msg.success) showErrorNotification(msg.message) + if (!msg.success) { + // Check if this was a disarm attempt and was not a force disarm + if (msg.was_disarming && !msg.was_force) { + store.dispatch(setForceDisarmModalOpened(true)) + } else { + showErrorNotification(msg.message) + } + } }) socket.socket.on( diff --git a/gcs/src/redux/slices/droneConnectionSlice.js b/gcs/src/redux/slices/droneConnectionSlice.js index 3a8b2e255..ff184e6e3 100644 --- a/gcs/src/redux/slices/droneConnectionSlice.js +++ b/gcs/src/redux/slices/droneConnectionSlice.js @@ -43,6 +43,8 @@ const initialState = { videoSource: null, videoMaximized: false, videoScale: 1, + + forceDisarmModalOpened: false, } const droneConnectionSlice = createSlice({ @@ -143,6 +145,9 @@ const droneConnectionSlice = createSlice({ setVideoScale: (state, action) => { state.videoScale = action.payload }, + setForceDisarmModalOpened: (state, action) => { + state.forceDisarmModalOpened = action.payload + }, // Emits emitIsConnectedToDrone: () => {}, @@ -187,6 +192,7 @@ const droneConnectionSlice = createSlice({ selectVideoSource: (state) => state.videoSource, selectVideoMaximized: (state) => state.videoMaximized, selectVideoScale: (state) => state.videoScale, + selectForceDisarmModalOpened: (state) => state.forceDisarmModalOpened, }, }) @@ -213,6 +219,7 @@ export const { setVideoSource, setVideoMaximized, setVideoScale, + setForceDisarmModalOpened, // Emitters emitIsConnectedToDrone, @@ -254,6 +261,7 @@ export const { selectVideoSource, selectVideoMaximized, selectVideoScale, + selectForceDisarmModalOpened, } = droneConnectionSlice.selectors export default droneConnectionSlice diff --git a/radio/app/controllers/armController.py b/radio/app/controllers/armController.py index c643fdc7b..ec0303266 100644 --- a/radio/app/controllers/armController.py +++ b/radio/app/controllers/armController.py @@ -47,7 +47,7 @@ def arm(self, force: bool = False) -> Response: self.drone.sendCommand( mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM, param1=1, # 0=disarm, 1=arm - param2=2989 if force else 0, # force arm/disarm + param2=21196 if force else 0, # force arm/disarm ) response = self.drone.wait_for_message( @@ -103,7 +103,7 @@ def disarm(self, force: bool = False) -> Response: self.drone.sendCommand( mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM, param1=0, # 0=disarm, 1=arm - param2=2989 if force else 0, # force arm/disarm + param2=21196 if force else 0, # force arm/disarm ) response = self.drone.wait_for_message( diff --git a/radio/app/endpoints/arm.py b/radio/app/endpoints/arm.py index a877e32ef..17fe6047d 100644 --- a/radio/app/endpoints/arm.py +++ b/radio/app/endpoints/arm.py @@ -2,7 +2,7 @@ import app.droneStatus as droneStatus from app import socketio -from app.utils import notConnectedError, missingParameterError +from app.utils import missingParameterError, notConnectedError class ArmDisarmType(TypedDict): @@ -32,4 +32,8 @@ def arm(data: ArmDisarmType) -> None: else: result = droneStatus.drone.armController.disarm(force) + # Add flag to indicate if this was a disarm attempt + result["was_disarming"] = not arm + result["was_force"] = force + socketio.emit("arm_disarm", result) From 58401f4a7ed495f73143057e8f8ac570017df620 Mon Sep 17 00:00:00 2001 From: Kush Makkapati Date: Sat, 13 Dec 2025 14:15:40 +0000 Subject: [PATCH 2/4] Update arm tests --- radio/tests/test_arm.py | 30 +++++++++++++++++++++++++++++- 1 file changed, 29 insertions(+), 1 deletion(-) diff --git a/radio/tests/test_arm.py b/radio/tests/test_arm.py index f3cc181a4..792aab07d 100644 --- a/radio/tests/test_arm.py +++ b/radio/tests/test_arm.py @@ -1,6 +1,6 @@ import time -import pytest +import pytest from flask_socketio.test_client import SocketIOTestClient from . import falcon_test @@ -38,6 +38,8 @@ def test_arm_disarm_normal(socketio_client: SocketIOTestClient, droneStatus) -> assert socketio_client.get_received()[0]["args"][0] == { "success": True, "message": "Armed successfully", + "was_disarming": False, + "was_force": False, } assert_drone_armed(droneStatus, armed=True) @@ -46,6 +48,8 @@ def test_arm_disarm_normal(socketio_client: SocketIOTestClient, droneStatus) -> assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Already armed", + "was_disarming": False, + "was_force": False, } assert_drone_armed(droneStatus, armed=True) @@ -53,6 +57,8 @@ def test_arm_disarm_normal(socketio_client: SocketIOTestClient, droneStatus) -> assert socketio_client.get_received()[0]["args"][0] == { "success": True, "message": "Disarmed successfully", + "was_disarming": True, + "was_force": False, } assert_drone_armed(droneStatus, armed=False) @@ -61,6 +67,8 @@ def test_arm_disarm_normal(socketio_client: SocketIOTestClient, droneStatus) -> assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Already disarmed", + "was_disarming": True, + "was_force": False, } assert_drone_armed(droneStatus, armed=False) @@ -73,6 +81,8 @@ def test_arm_disarm_force(socketio_client: SocketIOTestClient, droneStatus) -> N assert socketio_client.get_received()[0]["args"][0] == { "success": True, "message": "Armed successfully", + "was_disarming": False, + "was_force": True, } assert_drone_armed(droneStatus, armed=True) @@ -81,6 +91,8 @@ def test_arm_disarm_force(socketio_client: SocketIOTestClient, droneStatus) -> N assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Already armed", + "was_disarming": False, + "was_force": True, } assert_drone_armed(droneStatus, armed=True) @@ -88,6 +100,8 @@ def test_arm_disarm_force(socketio_client: SocketIOTestClient, droneStatus) -> N assert socketio_client.get_received()[0]["args"][0] == { "success": True, "message": "Disarmed successfully", + "was_disarming": True, + "was_force": True, } assert_drone_armed(droneStatus, armed=False) @@ -96,6 +110,8 @@ def test_arm_disarm_force(socketio_client: SocketIOTestClient, droneStatus) -> N assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Already disarmed", + "was_disarming": True, + "was_force": True, } assert_drone_armed(droneStatus, armed=False) @@ -107,11 +123,15 @@ def test_arm_disarm_exception(socketio_client: SocketIOTestClient, droneStatus): assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Could not arm, serial exception", + "was_disarming": False, + "was_force": False, } socketio_client.emit("arm_disarm", {"arm": True, "force": True}) assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Could not arm, serial exception", + "was_disarming": False, + "was_force": True, } socketio_client.emit("arm_disarm", {"arm": True}) @@ -121,11 +141,15 @@ def test_arm_disarm_exception(socketio_client: SocketIOTestClient, droneStatus): assert socketio_client.get_received()[1]["args"][0] == { "success": False, "message": "Could not disarm, serial exception", + "was_disarming": True, + "was_force": False, } socketio_client.emit("arm_disarm", {"arm": False, "force": True}) assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Could not disarm, serial exception", + "was_disarming": True, + "was_force": True, } socketio_client.emit("arm_disarm", {"arm": False}) socketio_client.get_received() @@ -170,10 +194,14 @@ def test_arm_no_gps(gps_failure) -> None: assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Could not arm, command not accepted", + "was_disarming": False, + "was_force": False, } socketio_client.emit("arm_disarm", {"arm": True, "force": True}) assert socketio_client.get_received()[0]["args"][0] == { "success": True, "message": "Armed successfully", + "was_disarming": False, + "was_force": True, } From 7cb6d69ce70557b4461ec96091201dda00352f93 Mon Sep 17 00:00:00 2001 From: Kush Makkapati Date: Sat, 13 Dec 2025 14:26:18 +0000 Subject: [PATCH 3/4] Update arming tests --- gcs/src/redux/middleware/socketMiddleware.js | 2 +- radio/app/controllers/armController.py | 61 +++++++++++-- radio/app/endpoints/arm.py | 4 - radio/tests/test_arm.py | 95 ++++++++++---------- 4 files changed, 105 insertions(+), 57 deletions(-) diff --git a/gcs/src/redux/middleware/socketMiddleware.js b/gcs/src/redux/middleware/socketMiddleware.js index fbf49b839..ac85c7e69 100644 --- a/gcs/src/redux/middleware/socketMiddleware.js +++ b/gcs/src/redux/middleware/socketMiddleware.js @@ -522,7 +522,7 @@ const socketMiddleware = (store) => { socket.socket.on(DroneSpecificSocketEvents.onArmDisarm, (msg) => { if (!msg.success) { // Check if this was a disarm attempt and was not a force disarm - if (msg.was_disarming && !msg.was_force) { + if (msg.data?.was_disarming && !msg.data?.was_force) { store.dispatch(setForceDisarmModalOpened(true)) } else { showErrorNotification(msg.message) diff --git a/radio/app/controllers/armController.py b/radio/app/controllers/armController.py index ec0303266..1110b7e4c 100644 --- a/radio/app/controllers/armController.py +++ b/radio/app/controllers/armController.py @@ -35,12 +35,23 @@ def arm(self, force: bool = False) -> Response: Response: The response from the arm command """ if self.drone.armed: - return {"success": False, "message": "Already armed"} + return { + "success": False, + "message": "Already armed", + "data": { + "was_disarming": False, + "was_force": force, + }, + } if not self.drone.reserve_message_type("COMMAND_ACK", self.controller_id): return { "success": False, "message": "Could not reserve COMMAND_ACK messages", + "data": { + "was_disarming": False, + "was_force": force, + }, } try: @@ -63,19 +74,37 @@ def arm(self, force: bool = False) -> Response: while not self.drone.armed: time.sleep(0.05) self.drone.logger.debug("ARMED") - return {"success": True, "message": "Armed successfully"} + return { + "success": False, + "message": "Armed successfully", + "data": { + "was_disarming": False, + "was_force": force, + }, + } else: self.drone.logger.debug("Arming failed") return { "success": False, "message": "Could not arm, command not accepted", + "data": { + "was_disarming": False, + "was_force": force, + }, } except Exception as e: self.drone.logger.error(e, exc_info=True) if self.drone.droneErrorCb: self.drone.droneErrorCb(str(e)) - return {"success": False, "message": "Could not arm, serial exception"} + return { + "success": False, + "message": "Could not arm, serial exception", + "data": { + "was_disarming": False, + "was_force": force, + }, + } finally: self.drone.release_message_type("COMMAND_ACK", self.controller_id) @@ -91,12 +120,23 @@ def disarm(self, force: bool = False) -> Response: Response: The response from the disarm command """ if not self.drone.armed: - return {"success": False, "message": "Already disarmed"} + return { + "success": False, + "message": "Already disarmed", + "data": { + "was_disarming": True, + "was_force": force, + }, + } if not self.drone.reserve_message_type("COMMAND_ACK", self.controller_id): return { "success": False, "message": "Could not reserve COMMAND_ACK messages", + "data": { + "was_disarming": True, + "was_force": force, + }, } try: @@ -119,12 +159,23 @@ def disarm(self, force: bool = False) -> Response: while self.drone.armed: time.sleep(0.05) self.drone.logger.debug("DISARMED") - return {"success": True, "message": "Disarmed successfully"} + return { + "success": True, + "message": "Disarmed successfully", + "data": { + "was_disarming": True, + "was_force": force, + }, + } else: self.drone.logger.debug("Could not disarm, command not accepted") return { "success": False, "message": "Could not disarm, command not accepted", + "data": { + "was_disarming": True, + "was_force": force, + }, } except Exception as e: diff --git a/radio/app/endpoints/arm.py b/radio/app/endpoints/arm.py index 17fe6047d..0fa43742c 100644 --- a/radio/app/endpoints/arm.py +++ b/radio/app/endpoints/arm.py @@ -32,8 +32,4 @@ def arm(data: ArmDisarmType) -> None: else: result = droneStatus.drone.armController.disarm(force) - # Add flag to indicate if this was a disarm attempt - result["was_disarming"] = not arm - result["was_force"] = force - socketio.emit("arm_disarm", result) diff --git a/radio/tests/test_arm.py b/radio/tests/test_arm.py index 792aab07d..2ea734a62 100644 --- a/radio/tests/test_arm.py +++ b/radio/tests/test_arm.py @@ -38,8 +38,10 @@ def test_arm_disarm_normal(socketio_client: SocketIOTestClient, droneStatus) -> assert socketio_client.get_received()[0]["args"][0] == { "success": True, "message": "Armed successfully", - "was_disarming": False, - "was_force": False, + "data": { + "was_disarming": False, + "was_force": False, + }, } assert_drone_armed(droneStatus, armed=True) @@ -48,8 +50,10 @@ def test_arm_disarm_normal(socketio_client: SocketIOTestClient, droneStatus) -> assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Already armed", - "was_disarming": False, - "was_force": False, + "data": { + "was_disarming": False, + "was_force": False, + }, } assert_drone_armed(droneStatus, armed=True) @@ -57,8 +61,10 @@ def test_arm_disarm_normal(socketio_client: SocketIOTestClient, droneStatus) -> assert socketio_client.get_received()[0]["args"][0] == { "success": True, "message": "Disarmed successfully", - "was_disarming": True, - "was_force": False, + "data": { + "was_disarming": True, + "was_force": False, + }, } assert_drone_armed(droneStatus, armed=False) @@ -67,8 +73,10 @@ def test_arm_disarm_normal(socketio_client: SocketIOTestClient, droneStatus) -> assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Already disarmed", - "was_disarming": True, - "was_force": False, + "data": { + "was_disarming": True, + "was_force": False, + }, } assert_drone_armed(droneStatus, armed=False) @@ -81,8 +89,10 @@ def test_arm_disarm_force(socketio_client: SocketIOTestClient, droneStatus) -> N assert socketio_client.get_received()[0]["args"][0] == { "success": True, "message": "Armed successfully", - "was_disarming": False, - "was_force": True, + "data": { + "was_disarming": False, + "was_force": True, + }, } assert_drone_armed(droneStatus, armed=True) @@ -91,8 +101,10 @@ def test_arm_disarm_force(socketio_client: SocketIOTestClient, droneStatus) -> N assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Already armed", - "was_disarming": False, - "was_force": True, + "data": { + "was_disarming": False, + "was_force": True, + }, } assert_drone_armed(droneStatus, armed=True) @@ -100,8 +112,10 @@ def test_arm_disarm_force(socketio_client: SocketIOTestClient, droneStatus) -> N assert socketio_client.get_received()[0]["args"][0] == { "success": True, "message": "Disarmed successfully", - "was_disarming": True, - "was_force": True, + "data": { + "was_disarming": False, + "was_force": True, + }, } assert_drone_armed(droneStatus, armed=False) @@ -110,8 +124,10 @@ def test_arm_disarm_force(socketio_client: SocketIOTestClient, droneStatus) -> N assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Already disarmed", - "was_disarming": True, - "was_force": True, + "data": { + "was_disarming": False, + "was_force": True, + }, } assert_drone_armed(droneStatus, armed=False) @@ -123,15 +139,19 @@ def test_arm_disarm_exception(socketio_client: SocketIOTestClient, droneStatus): assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Could not arm, serial exception", - "was_disarming": False, - "was_force": False, + "data": { + "was_disarming": False, + "was_force": False, + }, } socketio_client.emit("arm_disarm", {"arm": True, "force": True}) assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Could not arm, serial exception", - "was_disarming": False, - "was_force": True, + "data": { + "was_disarming": False, + "was_force": True, + }, } socketio_client.emit("arm_disarm", {"arm": True}) @@ -141,15 +161,19 @@ def test_arm_disarm_exception(socketio_client: SocketIOTestClient, droneStatus): assert socketio_client.get_received()[1]["args"][0] == { "success": False, "message": "Could not disarm, serial exception", - "was_disarming": True, - "was_force": False, + "data": { + "was_disarming": True, + "was_force": False, + }, } socketio_client.emit("arm_disarm", {"arm": False, "force": True}) assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Could not disarm, serial exception", - "was_disarming": True, - "was_force": True, + "data": { + "was_disarming": True, + "was_force": True, + }, } socketio_client.emit("arm_disarm", {"arm": False}) socketio_client.get_received() @@ -182,26 +206,3 @@ def test_arm_disarm_wrong_args(socketio_client: SocketIOTestClient, droneStatus) assert result["args"][0] == { "message": "Request to endpoint arm_disarm missing value for parameter: arm." } - - -@pytest.mark.skip("GPS failure fixture is broken") -def test_arm_no_gps(gps_failure) -> None: - from . import socketio_client - - # Test losing GPS lock when attempting to arm. Assert needs to be outside the context manager because - socketio_client.emit("arm_disarm", {"arm": True}) - - assert socketio_client.get_received()[0]["args"][0] == { - "success": False, - "message": "Could not arm, command not accepted", - "was_disarming": False, - "was_force": False, - } - socketio_client.emit("arm_disarm", {"arm": True, "force": True}) - - assert socketio_client.get_received()[0]["args"][0] == { - "success": True, - "message": "Armed successfully", - "was_disarming": False, - "was_force": True, - } From 8adeadce2b2cdbd76cc515714850ddb780dadc78 Mon Sep 17 00:00:00 2001 From: Kush Makkapati Date: Sun, 14 Dec 2025 21:53:42 +0000 Subject: [PATCH 4/4] Fix arm tests --- radio/app/controllers/armController.py | 67 ++++----- radio/tests/helpers.py | 4 +- radio/tests/test_arm.py | 183 +++++++++++++++++++++---- 3 files changed, 180 insertions(+), 74 deletions(-) diff --git a/radio/app/controllers/armController.py b/radio/app/controllers/armController.py index 1110b7e4c..ccf89fd4f 100644 --- a/radio/app/controllers/armController.py +++ b/radio/app/controllers/armController.py @@ -34,24 +34,19 @@ def arm(self, force: bool = False) -> Response: Returns: Response: The response from the arm command """ + return_data = { + "was_disarming": False, + "was_force": force, + } + if self.drone.armed: - return { - "success": False, - "message": "Already armed", - "data": { - "was_disarming": False, - "was_force": force, - }, - } + return {"success": False, "message": "Already armed", "data": return_data} if not self.drone.reserve_message_type("COMMAND_ACK", self.controller_id): return { "success": False, "message": "Could not reserve COMMAND_ACK messages", - "data": { - "was_disarming": False, - "was_force": force, - }, + "data": return_data, } try: @@ -75,22 +70,16 @@ def arm(self, force: bool = False) -> Response: time.sleep(0.05) self.drone.logger.debug("ARMED") return { - "success": False, + "success": True, "message": "Armed successfully", - "data": { - "was_disarming": False, - "was_force": force, - }, + "data": return_data, } else: self.drone.logger.debug("Arming failed") return { "success": False, "message": "Could not arm, command not accepted", - "data": { - "was_disarming": False, - "was_force": force, - }, + "data": return_data, } except Exception as e: @@ -100,10 +89,7 @@ def arm(self, force: bool = False) -> Response: return { "success": False, "message": "Could not arm, serial exception", - "data": { - "was_disarming": False, - "was_force": force, - }, + "data": return_data, } finally: self.drone.release_message_type("COMMAND_ACK", self.controller_id) @@ -119,24 +105,23 @@ def disarm(self, force: bool = False) -> Response: Returns: Response: The response from the disarm command """ + return_data = { + "was_disarming": True, + "was_force": force, + } + if not self.drone.armed: return { "success": False, "message": "Already disarmed", - "data": { - "was_disarming": True, - "was_force": force, - }, + "data": return_data, } if not self.drone.reserve_message_type("COMMAND_ACK", self.controller_id): return { "success": False, "message": "Could not reserve COMMAND_ACK messages", - "data": { - "was_disarming": True, - "was_force": force, - }, + "data": return_data, } try: @@ -162,26 +147,24 @@ def disarm(self, force: bool = False) -> Response: return { "success": True, "message": "Disarmed successfully", - "data": { - "was_disarming": True, - "was_force": force, - }, + "data": return_data, } else: self.drone.logger.debug("Could not disarm, command not accepted") return { "success": False, "message": "Could not disarm, command not accepted", - "data": { - "was_disarming": True, - "was_force": force, - }, + "data": return_data, } except Exception as e: self.drone.logger.error(e, exc_info=True) if self.drone.droneErrorCb: self.drone.droneErrorCb(str(e)) - return {"success": False, "message": "Could not disarm, serial exception"} + return { + "success": False, + "message": "Could not disarm, serial exception", + "data": return_data, + } finally: self.drone.release_message_type("COMMAND_ACK", self.controller_id) diff --git a/radio/tests/helpers.py b/radio/tests/helpers.py index 84afabf88..09969f2ba 100644 --- a/radio/tests/helpers.py +++ b/radio/tests/helpers.py @@ -15,9 +15,7 @@ class FakeTCP: """ @staticmethod - def return_serial_exception( - condition=None, type=None, blocking=False, timeout=None - ) -> None: + def return_serial_exception(*args, **kwargs) -> None: raise SerialException( "Test SerialException generated by tests.FakeTCP context manager." ) diff --git a/radio/tests/test_arm.py b/radio/tests/test_arm.py index 2ea734a62..a242f02fb 100644 --- a/radio/tests/test_arm.py +++ b/radio/tests/test_arm.py @@ -8,33 +8,58 @@ @pytest.fixture(scope="module", autouse=True) -def run_once_after_all_tests(): +def run_once_before_all_tests(): """ - Saves the valid connection string then ensures that the drone connection is established again after the tests have run + Ensures that the drone is disarmed once and the proper flight mode is set before all tests in this module """ from app import droneStatus - assert not droneStatus.drone.armed + # Setup: Disarm before tests and set the flight mode + droneStatus.drone.master.arducopter_disarm() + wait_for_disarm(droneStatus) + droneStatus.drone.master.set_mode_apm("STABILIZE") + yield - assert not droneStatus.drone.armed + + +@pytest.fixture(autouse=True) +def disarm_after_each_test(): + """ + Ensures that the drone is disarmed after each individual test + """ + from app import droneStatus + + # Run the test + yield + + # Teardown: Disarm after each test + droneStatus.drone.master.arducopter_disarm() + wait_for_disarm(droneStatus) + + +def wait_for_disarm(droneStatus) -> None: + """Waits until the drone is disarmed""" + timeout = time.time() + 10 # 10 seconds from now + while droneStatus.drone.armed: + if time.time() > timeout: + raise TimeoutError("Timed out waiting for drone to disarm") + time.sleep(0.05) def assert_drone_armed(droneStatus, armed: bool) -> None: + time.sleep(1) # Give some time for the state to update assert droneStatus.drone.armed == armed assert bool(droneStatus.drone.master.motors_armed()) == armed @falcon_test(pass_drone_status=True) -def test_arm_disarm_normal(socketio_client: SocketIOTestClient, droneStatus) -> None: - time.sleep(10) - # Test arm normally +def test_arm_succeeds_when_disarmed( + socketio_client: SocketIOTestClient, droneStatus +) -> None: assert_drone_armed(droneStatus, armed=False) - socketio_client.emit( - "arm_disarm", - { - "arm": True, - }, - ) + + socketio_client.emit("arm_disarm", {"arm": True}) + assert socketio_client.get_received()[0]["args"][0] == { "success": True, "message": "Armed successfully", @@ -45,8 +70,17 @@ def test_arm_disarm_normal(socketio_client: SocketIOTestClient, droneStatus) -> } assert_drone_armed(droneStatus, armed=True) - # Test arming failure if already armed + +@falcon_test(pass_drone_status=True) +def test_arm_fails_when_already_armed( + socketio_client: SocketIOTestClient, droneStatus +) -> None: + droneStatus.drone.master.arducopter_arm() + time.sleep(1) + assert_drone_armed(droneStatus, armed=True) + socketio_client.emit("arm_disarm", {"arm": True}) + assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Already armed", @@ -57,7 +91,17 @@ def test_arm_disarm_normal(socketio_client: SocketIOTestClient, droneStatus) -> } assert_drone_armed(droneStatus, armed=True) + +@falcon_test(pass_drone_status=True) +def test_disarm_succeeds_when_armed( + socketio_client: SocketIOTestClient, droneStatus +) -> None: + droneStatus.drone.master.arducopter_arm() + time.sleep(1) + assert_drone_armed(droneStatus, armed=True) + socketio_client.emit("arm_disarm", {"arm": False}) + assert socketio_client.get_received()[0]["args"][0] == { "success": True, "message": "Disarmed successfully", @@ -68,8 +112,15 @@ def test_arm_disarm_normal(socketio_client: SocketIOTestClient, droneStatus) -> } assert_drone_armed(droneStatus, armed=False) - # Test disarm failure when not armed + +@falcon_test(pass_drone_status=True) +def test_disarm_fails_when_already_disarmed( + socketio_client: SocketIOTestClient, droneStatus +) -> None: + assert_drone_armed(droneStatus, armed=False) + socketio_client.emit("arm_disarm", {"arm": False}) + assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Already disarmed", @@ -82,10 +133,13 @@ def test_arm_disarm_normal(socketio_client: SocketIOTestClient, droneStatus) -> @falcon_test(pass_drone_status=True) -def test_arm_disarm_force(socketio_client: SocketIOTestClient, droneStatus) -> None: - # Test arm normally +def test_force_arm_succeeds_when_disarmed( + socketio_client: SocketIOTestClient, droneStatus +) -> None: assert_drone_armed(droneStatus, armed=False) + socketio_client.emit("arm_disarm", {"arm": True, "force": True}) + assert socketio_client.get_received()[0]["args"][0] == { "success": True, "message": "Armed successfully", @@ -96,8 +150,17 @@ def test_arm_disarm_force(socketio_client: SocketIOTestClient, droneStatus) -> N } assert_drone_armed(droneStatus, armed=True) - # Test arming failure if already armed + +@falcon_test(pass_drone_status=True) +def test_force_arm_fails_when_already_armed( + socketio_client: SocketIOTestClient, droneStatus +) -> None: + droneStatus.drone.master.arducopter_arm() + time.sleep(1) + assert_drone_armed(droneStatus, armed=True) + socketio_client.emit("arm_disarm", {"arm": True, "force": True}) + assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Already armed", @@ -108,24 +171,41 @@ def test_arm_disarm_force(socketio_client: SocketIOTestClient, droneStatus) -> N } assert_drone_armed(droneStatus, armed=True) + +@falcon_test(pass_drone_status=True) +def test_force_disarm_succeeds_when_armed( + socketio_client: SocketIOTestClient, droneStatus +) -> None: + droneStatus.drone.master.arducopter_arm() + time.sleep(1) + assert_drone_armed(droneStatus, armed=True) + socketio_client.emit("arm_disarm", {"arm": False, "force": True}) + assert socketio_client.get_received()[0]["args"][0] == { "success": True, "message": "Disarmed successfully", "data": { - "was_disarming": False, + "was_disarming": True, "was_force": True, }, } assert_drone_armed(droneStatus, armed=False) - # Test disarm failure when not armed + +@falcon_test(pass_drone_status=True) +def test_force_disarm_fails_when_already_disarmed( + socketio_client: SocketIOTestClient, droneStatus +) -> None: + assert_drone_armed(droneStatus, armed=False) + socketio_client.emit("arm_disarm", {"arm": False, "force": True}) + assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Already disarmed", "data": { - "was_disarming": False, + "was_disarming": True, "was_force": True, }, } @@ -133,9 +213,14 @@ def test_arm_disarm_force(socketio_client: SocketIOTestClient, droneStatus) -> N @falcon_test(pass_drone_status=True) -def test_arm_disarm_exception(socketio_client: SocketIOTestClient, droneStatus): +def test_arm_fails_with_serial_exception( + socketio_client: SocketIOTestClient, droneStatus +) -> None: + assert_drone_armed(droneStatus, armed=False) + with FakeTCP(): socketio_client.emit("arm_disarm", {"arm": True}) + assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Could not arm, serial exception", @@ -144,7 +229,17 @@ def test_arm_disarm_exception(socketio_client: SocketIOTestClient, droneStatus): "was_force": False, }, } + + +@falcon_test(pass_drone_status=True) +def test_force_arm_fails_with_serial_exception( + socketio_client: SocketIOTestClient, droneStatus +) -> None: + assert_drone_armed(droneStatus, armed=False) + + with FakeTCP(): socketio_client.emit("arm_disarm", {"arm": True, "force": True}) + assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Could not arm, serial exception", @@ -154,11 +249,19 @@ def test_arm_disarm_exception(socketio_client: SocketIOTestClient, droneStatus): }, } - socketio_client.emit("arm_disarm", {"arm": True}) + +@falcon_test(pass_drone_status=True) +def test_disarm_fails_with_serial_exception( + socketio_client: SocketIOTestClient, droneStatus +) -> None: + droneStatus.drone.master.arducopter_arm() + time.sleep(1) + assert_drone_armed(droneStatus, armed=True) with FakeTCP(): socketio_client.emit("arm_disarm", {"arm": False}) - assert socketio_client.get_received()[1]["args"][0] == { + + assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Could not disarm, serial exception", "data": { @@ -166,7 +269,19 @@ def test_arm_disarm_exception(socketio_client: SocketIOTestClient, droneStatus): "was_force": False, }, } + + +@falcon_test(pass_drone_status=True) +def test_force_disarm_fails_with_serial_exception( + socketio_client: SocketIOTestClient, droneStatus +) -> None: + droneStatus.drone.master.arducopter_arm() + time.sleep(1) + assert_drone_armed(droneStatus, armed=True) + + with FakeTCP(): socketio_client.emit("arm_disarm", {"arm": False, "force": True}) + assert socketio_client.get_received()[0]["args"][0] == { "success": False, "message": "Could not disarm, serial exception", @@ -175,22 +290,29 @@ def test_arm_disarm_exception(socketio_client: SocketIOTestClient, droneStatus): "was_force": True, }, } - socketio_client.emit("arm_disarm", {"arm": False}) - socketio_client.get_received() - assert_drone_armed(droneStatus, armed=False) @falcon_test(pass_drone_status=True) -def test_arm_disarm_no_drone(socketio_client: SocketIOTestClient, droneStatus): +def test_arm_fails_when_no_drone_connected( + socketio_client: SocketIOTestClient, droneStatus +) -> None: with NoDrone(): socketio_client.emit("arm_disarm", {"arm": True}) + result = socketio_client.get_received()[0] assert result["name"] == "connection_error" assert result["args"][0] == { "message": "Must be connected to the drone to arm or disarm." } + +@falcon_test(pass_drone_status=True) +def test_force_disarm_fails_when_no_drone_connected( + socketio_client: SocketIOTestClient, droneStatus +) -> None: + with NoDrone(): socketio_client.emit("arm_disarm", {"arm": False, "force": True}) + result = socketio_client.get_received()[0] assert result["name"] == "connection_error" assert result["args"][0] == { @@ -199,8 +321,11 @@ def test_arm_disarm_no_drone(socketio_client: SocketIOTestClient, droneStatus): @falcon_test(pass_drone_status=True) -def test_arm_disarm_wrong_args(socketio_client: SocketIOTestClient, droneStatus): +def test_arm_disarm_fails_with_missing_arm_parameter( + socketio_client: SocketIOTestClient, droneStatus +) -> None: socketio_client.emit("arm_disarm", {}) + result = socketio_client.get_received()[0] assert result["name"] == "drone_error" assert result["args"][0] == {