Skip to content
Open
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
420 changes: 420 additions & 0 deletions gcs/src/components/config/failsafe.jsx

Large diffs are not rendered by default.

11 changes: 9 additions & 2 deletions gcs/src/config.jsx
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,9 @@ import { useEffect } from "react"
import { Tabs } from "@mantine/core"

// Custom component and helpers
import Failsafes from "./components/config/failsafe"
import FlightModes from "./components/config/flightModes"
import Ftp from "./components/config/ftp"
import Gripper from "./components/config/gripper"
import Motortestpanel from "./components/config/motorTest"
import RadioCalibration from "./components/config/radioCalibration"
Expand All @@ -20,7 +22,6 @@ import NoDroneConnected from "./components/noDroneConnected"

// Redux
import { useDispatch, useSelector } from "react-redux"
import Ftp from "./components/config/ftp"
import { selectActiveTab, setActiveTab } from "./redux/slices/configSlice"
import { selectConnectedToDrone } from "./redux/slices/droneConnectionSlice"
import SerialPorts from "./components/config/serialPorts"
Expand All @@ -41,7 +42,7 @@ export default function Config() {
return (
<Layout currentPage="config">
{connected ? (
<div className="w-full h-full">
<div className="size-full">
<Tabs
orientation="vertical"
color={"red"}
Expand All @@ -55,6 +56,7 @@ export default function Config() {
<Tabs.Tab value="motor_test">Motor Test</Tabs.Tab>
<Tabs.Tab value="rc_calibration">RC Calibration</Tabs.Tab>
<Tabs.Tab value="flightmodes">Flight modes</Tabs.Tab>
<Tabs.Tab value="failsafes">Failsafes</Tabs.Tab>
<Tabs.Tab value="servo">Servo Output</Tabs.Tab>
<Tabs.Tab value="serial_ports">Serial Ports</Tabs.Tab>
<Tabs.Tab value="ftp">FTP</Tabs.Tab>
Expand All @@ -79,6 +81,11 @@ export default function Config() {
<FlightModes />
</div>
</Tabs.Panel>
<Tabs.Panel value="failsafes">
<div className="size-full">
<Failsafes />
</div>
</Tabs.Panel>
<Tabs.Panel value="servo">
<div className={paddingTop}>
<ServoOutput />
Expand Down
19 changes: 19 additions & 0 deletions gcs/src/redux/middleware/emitters.js
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
import { showErrorNotification } from "../../helpers/notification"
import {
emitBatchSetRcConfigParams,
emitGetFailsafeConfig,
emitBatchSetServoConfigParams,
emitGetFlightModeConfig,
emitGetFrameConfig,
Expand All @@ -14,6 +15,7 @@ import {
emitSetFlightModeChannel,
emitSetGripper,
emitSetGripperConfigParam,
emitSetFailsafeConfigParam,
emitSetGripperDisabled,
emitSetGripperEnabled,
emitSetRcConfigParam,
Expand All @@ -22,6 +24,7 @@ import {
emitTestAllMotors,
emitTestMotorSequence,
emitTestOneMotor,
setRefreshingFailsafeConfigData,
emitTestServoPwm,
setRefreshingGripperConfigData,
} from "../slices/configSlice"
Expand Down Expand Up @@ -351,6 +354,22 @@ export function handleEmitters(socket, store, action) {
= CONFIG =
==========
*/
{
emitter: emitGetFailsafeConfig,
callback: () => {
socket.socket.emit("get_failsafe_config")
store.dispatch(setRefreshingFailsafeConfigData(true))
},
},
{
emitter: emitSetFailsafeConfigParam,
callback: () => {
socket.socket.emit("set_failsafe_config_param", {
param_id: action.payload.param_id,
value: action.payload.value,
})
},
},
{
emitter: emitGetGripperEnabled,
callback: () => socket.socket.emit("get_gripper_enabled"),
Expand Down
27 changes: 27 additions & 0 deletions gcs/src/redux/middleware/socketMiddleware.js
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ import {
emitGetGripperConfig,
setChannelsConfig,
setCurrentPwmValue,
setFailsafeConfig,
setFlightModeChannel,
setFlightModesList,
setFrameClass,
Expand All @@ -61,13 +62,15 @@ import {
setNumberOfMotors,
setRadioCalibrationModalOpen,
setRadioPwmChannels,
setRefreshingFailsafeConfigData,
setRefreshingFlightModeData,
setRefreshingGripperConfigData,
setSerialPortsConfig,
setServoConfig,
setServoPwmOutputs,
setShowMotorTestWarningModal,
updateChannelsConfigParam,
updateFailsafeConfigParam,
updateGripperConfigParam,
updateSerialPortConfigParam,
updateServoConfigParam,
Expand Down Expand Up @@ -195,12 +198,14 @@ const MissionSpecificSocketEvents = Object.freeze({
})

const ConfigSpecificSocketEvents = Object.freeze({
onFailsafeConfig: "failsafe_config",
onGripperEnabled: "is_gripper_enabled",
onSetGripperEnabledResult: "set_gripper_enabled_result",
onSetGripperDisabledResult: "set_gripper_disabled_result",
onSetGripperResult: "set_gripper_result",
onGripperConfig: "gripper_config",
setGripperParamResult: "set_gripper_param_result",
setFailsafeParamResult: "set_failsafe_param_result",
onMotorTestResult: "motor_test_result",
onFlightModeConfig: "flight_mode_config",
onSetFlightModeResult: "set_flight_mode_result",
Expand Down Expand Up @@ -1237,6 +1242,11 @@ const socketMiddleware = (store) => {
= CONFIG =
==========
*/
socket.socket.on(ConfigSpecificSocketEvents.onFailsafeConfig, (msg) => {
store.dispatch(setFailsafeConfig(msg.params))
store.dispatch(setRefreshingFailsafeConfigData(false))
})

socket.socket.on(
ConfigSpecificSocketEvents.onGripperEnabled,
(enabled) => {
Expand Down Expand Up @@ -1303,6 +1313,23 @@ const socketMiddleware = (store) => {
},
)

socket.socket.on(
ConfigSpecificSocketEvents.setFailsafeParamResult,
(msg) => {
if (msg.success) {
showSuccessNotification(msg.message)
store.dispatch(
updateFailsafeConfigParam({
param_id: msg.param_id,
value: msg.value,
}),
)
Comment on lines +1319 to +1326
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

Can you also update the params dict in redux when a param is set successfully so it updates on the params page as well; look at the flight modes config to see how that's done.

} else {
showErrorNotification(msg.message)
}
},
)

socket.socket.on(
ConfigSpecificSocketEvents.onMotorTestResult,
(msg) => {
Expand Down
27 changes: 27 additions & 0 deletions gcs/src/redux/slices/configSlice.js
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@ const configSlice = createSlice({
name: "config",
initialState: {
activeTab: null,
failsafeConfig: {},
refreshingFailsafeConfigData: false,
getGripperEnabled: false,
gripperConfig: {},
refreshingGripperConfigData: false,
Expand Down Expand Up @@ -82,6 +84,19 @@ const configSlice = createSlice({
if (state.gripperConfig[param_id] === value) return
state.gripperConfig[param_id] = value
},
setFailsafeConfig: (state, action) => {
if (action.payload === state.failsafeConfig) return
state.failsafeConfig = action.payload
},
updateFailsafeConfigParam: (state, action) => {
const { param_id, value } = action.payload
if (state.failsafeConfig[param_id] === value) return
state.failsafeConfig[param_id] = value
},
setRefreshingFailsafeConfigData: (state, action) => {
if (action.payload === state.refreshingFailsafeConfigData) return
state.refreshingFailsafeConfigData = action.payload
},
setRefreshingGripperConfigData: (state, action) => {
if (action.payload === state.refreshingGripperConfigData) return
state.refreshingGripperConfigData = action.payload
Expand Down Expand Up @@ -214,11 +229,13 @@ const configSlice = createSlice({
},

// Emits
emitGetFailsafeConfig: () => {},
emitGetGripperEnabled: () => {},
emitSetGripperEnabled: () => {},
emitSetGripperDisabled: () => {},
emitGetGripperConfig: () => {},
emitSetGripperConfigParam: () => {},
emitSetFailsafeConfigParam: () => {},
emitGetFlightModeConfig: () => {},
emitSetFlightMode: () => {},
emitSetFlightModeChannel: () => {},
Expand All @@ -241,6 +258,9 @@ const configSlice = createSlice({
},
selectors: {
selectActiveTab: (state) => state.activeTab,
selectFailsafeConfig: (state) => state.failsafeConfig,
selectRefreshingFailsafeConfigData: (state) =>
state.refreshingFailsafeConfigData,
selectGetGripperEnabled: (state) => state.getGripperEnabled,
selectGripperConfig: (state) => state.gripperConfig,
selectRefreshingGripperConfigData: (state) =>
Expand All @@ -266,9 +286,12 @@ const configSlice = createSlice({

export const {
setActiveTab,
setFailsafeConfig,
setGetGripperEnabled,
setGripperConfig,
updateGripperConfigParam,
updateFailsafeConfigParam,
setRefreshingFailsafeConfigData,
setRefreshingGripperConfigData,
setFlightModesList,
setFlightModeChannel,
Expand All @@ -290,11 +313,13 @@ export const {
setSerialPortsConfig,
updateSerialPortConfigParam,

emitGetFailsafeConfig,
emitGetGripperEnabled,
emitSetGripperEnabled,
emitSetGripperDisabled,
emitGetGripperConfig,
emitSetGripperConfigParam,
emitSetFailsafeConfigParam,
emitGetFlightModeConfig,
emitSetFlightMode,
emitSetFlightModeChannel,
Expand All @@ -318,6 +343,8 @@ export const {

export const {
selectActiveTab,
selectFailsafeConfig,
selectRefreshingFailsafeConfigData,
selectGetGripperEnabled,
selectGripperConfig,
selectRefreshingGripperConfigData,
Expand Down
81 changes: 81 additions & 0 deletions radio/app/controllers/failsafeController.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
from __future__ import annotations

from typing import TYPE_CHECKING

from app.customTypes import Number, VehicleType

if TYPE_CHECKING:
from app.drone import Drone

COMMON_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",
]


class FailsafeController:
def __init__(self, drone: Drone) -> None:
self.drone = drone

self.params: dict = {}

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.getSingleParam(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:
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

What's the difference between getFailsafeParams and getConfig? They look like they do the same thing?

"""
Gets the gripper related parameters from the drone.
"""
self.drone.logger.debug("Fetching gripper parameters")
Comment on lines +77 to +79
Copy link

Copilot AI Mar 29, 2026

Choose a reason for hiding this comment

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

getFailsafeParams docstring and log messages look copy/pasted from the gripper controller (mentions "gripper" and "from the drone"), but this method is reading from the cached params controller. This makes debugging confusing; please update the wording to refer to failsafe params and clarify it's reading from cache.

Suggested change
Gets the gripper related parameters from the drone.
"""
self.drone.logger.debug("Fetching gripper parameters")
Loads the failsafe-related parameters via the cached params controller.
"""
self.drone.logger.debug("Refreshing cached failsafe parameters")

Copilot uses AI. Check for mistakes.
Comment on lines +77 to +79
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

Gripper?

for param in self.valid_params:
self.params[param] = self.drone.paramsController.getSingleParam(param)
6 changes: 3 additions & 3 deletions radio/app/controllers/flightModesController.py
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down Expand Up @@ -87,7 +87,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,
Expand Down Expand Up @@ -219,7 +219,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)
Expand Down
4 changes: 2 additions & 2 deletions radio/app/controllers/frameController.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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()

Expand Down
Loading
Loading