Skip to content
Merged
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
52 changes: 52 additions & 0 deletions gcs/src/components/dashboard/ForceDisarmModal.jsx
Original file line number Diff line number Diff line change
@@ -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 (
<Modal
opened={isOpen}
onClose={handleCancel}
title="Failed to Disarm"
centered
>
<div className="flex flex-col gap-4">
<Text>
The aircraft failed to disarm normally. This could be because the
aircraft is still in the air or has other safety concerns.
</Text>
<Text weight={700} color="red">
Do you want to force disarm the aircraft?
</Text>
<Text size="sm" color="dimmed">
Warning: Force disarming bypasses safety checks and could cause the
aircraft to crash if it's still airborne.
</Text>
<div className="flex gap-2">
<Button onClick={handleCancel} variant="default" className="grow">
Cancel
</Button>
<Button onClick={handleForceDisarm} color="red" className="grow">
Force Disarm
</Button>
</div>
</div>
</Modal>
)
}
12 changes: 8 additions & 4 deletions gcs/src/dashboard.jsx
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand All @@ -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()
Expand Down Expand Up @@ -353,6 +356,7 @@ export default function Dashboard() {
</ResizableBox>
</div>
</div>
<ForceDisarmModal />
</Layout>
)
}
10 changes: 9 additions & 1 deletion gcs/src/redux/middleware/socketMiddleware.js
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ import {
setConnectionModal,
setConnectionStatus,
setFetchingComPorts,
setForceDisarmModalOpened,
setSelectedComPorts,
} from "../slices/droneConnectionSlice"

Expand Down Expand Up @@ -529,7 +530,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.data?.was_disarming && !msg.data?.was_force) {
store.dispatch(setForceDisarmModalOpened(true))
} else {
showErrorNotification(msg.message)
}
}
})

socket.socket.on(
Expand Down
8 changes: 8 additions & 0 deletions gcs/src/redux/slices/droneConnectionSlice.js
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@ const initialState = {
videoSource: null,
videoMaximized: false,
videoScale: 1,

forceDisarmModalOpened: false,
}

const droneConnectionSlice = createSlice({
Expand Down Expand Up @@ -143,6 +145,9 @@ const droneConnectionSlice = createSlice({
setVideoScale: (state, action) => {
state.videoScale = action.payload
},
setForceDisarmModalOpened: (state, action) => {
state.forceDisarmModalOpened = action.payload
},

// Emits
emitIsConnectedToDrone: () => {},
Expand Down Expand Up @@ -187,6 +192,7 @@ const droneConnectionSlice = createSlice({
selectVideoSource: (state) => state.videoSource,
selectVideoMaximized: (state) => state.videoMaximized,
selectVideoScale: (state) => state.videoScale,
selectForceDisarmModalOpened: (state) => state.forceDisarmModalOpened,
},
})

Expand All @@ -213,6 +219,7 @@ export const {
setVideoSource,
setVideoMaximized,
setVideoScale,
setForceDisarmModalOpened,

// Emitters
emitIsConnectedToDrone,
Expand Down Expand Up @@ -254,6 +261,7 @@ export const {
selectVideoSource,
selectVideoMaximized,
selectVideoScale,
selectForceDisarmModalOpened,
} = droneConnectionSlice.selectors

export default droneConnectionSlice
50 changes: 42 additions & 8 deletions radio/app/controllers/armController.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,20 +34,26 @@ 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"}
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": return_data,
}

try:
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
Comment thread
1Blademaster marked this conversation as resolved.
)

response = self.drone.wait_for_message(
Expand All @@ -63,19 +69,28 @@ 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": True,
"message": "Armed successfully",
"data": return_data,
}
else:
self.drone.logger.debug("Arming failed")
return {
"success": False,
"message": "Could not arm, command not accepted",
"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 arm, serial exception"}
return {
"success": False,
"message": "Could not arm, serial exception",
"data": return_data,
}
finally:
self.drone.release_message_type("COMMAND_ACK", self.controller_id)

Expand All @@ -90,20 +105,30 @@ 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"}
return {
"success": False,
"message": "Already disarmed",
"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": return_data,
}

try:
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
Comment thread
1Blademaster marked this conversation as resolved.
)

response = self.drone.wait_for_message(
Expand All @@ -119,18 +144,27 @@ 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": return_data,
}
else:
self.drone.logger.debug("Could not disarm, command not accepted")
return {
"success": False,
"message": "Could not disarm, command not accepted",
"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)
2 changes: 1 addition & 1 deletion radio/app/endpoints/arm.py
Original file line number Diff line number Diff line change
Expand Up @@ -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):
Expand Down
4 changes: 1 addition & 3 deletions radio/tests/helpers.py
Original file line number Diff line number Diff line change
Expand Up @@ -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."
)
Expand Down
Loading