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
2 changes: 1 addition & 1 deletion .github/workflows/python_tests.yml
Original file line number Diff line number Diff line change
Expand Up @@ -39,5 +39,5 @@ jobs:

- name: Test with pytest
working-directory: radio
timeout-minutes: 25
timeout-minutes: 15
run: pytest --log-cli-level=DEBUG
2 changes: 2 additions & 0 deletions gcs/src/helpers/socket.js
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,12 @@ import { io } from "socket.io-client"

class SocketConnection {
socket
telemetrySocket
socketEndpoint = import.meta.env.VITE_BACKEND_URL

constructor() {
this.socket = io(this.socketEndpoint)
this.telemetrySocket = io(this.socketEndpoint + "/telemetry")
}
}

Expand Down
6 changes: 5 additions & 1 deletion gcs/src/redux/middleware/emitters.js
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ import {
emitRefreshParams,
emitSetMultipleParams,
} from "../slices/paramsSlice"
import { resetMessages } from "../slices/statusTextSlice"

export function handleEmitters(socket, store, action) {
if (!socket) return
Expand All @@ -73,7 +74,10 @@ export function handleEmitters(socket, store, action) {
},
{
emitter: emitConnectToDrone,
callback: () => socket.socket.emit("connect_to_drone", action.payload),
callback: () => {
socket.socket.emit("connect_to_drone", action.payload)
store.dispatch(resetMessages())
},
},
{
emitter: emitStartForwarding,
Expand Down
176 changes: 101 additions & 75 deletions gcs/src/redux/middleware/socketMiddleware.js
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ import {
setShownParams,
updateParamValue,
} from "../slices/paramsSlice.js"
import { pushMessage, resetMessages } from "../slices/statusTextSlice.js"
import { pushMessage } from "../slices/statusTextSlice.js"
import { handleEmitters } from "./emitters.js"

const SocketEvents = Object.freeze({
Expand Down Expand Up @@ -354,13 +354,109 @@ const socketMiddleware = (store) => {
store.dispatch(setAutoPilotRebootModalOpen(false))
store.dispatch(setShouldFetchAllMissionsOnDashboard(true))
store.dispatch(setShowMotorTestWarningModal(true))
store.dispatch(resetMessages())
})

// Link stats
socket.socket.on(SocketEvents.linkDebugStats, (msg) => {
window.ipcRenderer.invoke("app:update-link-stats", msg)
})

/*
Telemetry Socket Connection Events
*/
socket.telemetrySocket.on("connect", () => {
console.log(
`Connected to telemetry socket: ${socket.telemetrySocket.id}`,
)
})

socket.telemetrySocket.on("disconnect", () => {
console.log(
`Disconnected from telemetry socket: ${socket.telemetrySocket.id}`,
)
})

socket.telemetrySocket.on("connect_error", (error) => {
console.error("Telemetry socket connection error:", error)
})

// I don't understand whatsoever why this doesn't work with the standard
// on method.
socket.telemetrySocket.onAny((eventName, ...args) => {
if (eventName !== DroneSpecificSocketEvents.onIncomingMsg) {
return
}

const msg = args[0]

Comment thread
1Blademaster marked this conversation as resolved.
incomingMessageHandler(msg)

// Data points on dashboard, the below code updates the value in the store when a new message
// comes in in the type of specificData.
const packetType = msg.mavpackettype
const storeState = store.getState()
if (storeState !== undefined) {
const extraDroneData = storeState.droneInfo.extraDroneData
const updatedExtraDroneData = extraDroneData.map((dataItem) => {
if (dataItem.currently_selected.startsWith(packetType)) {
const specificData = dataItem.currently_selected.split(".")[1]
if (Object.prototype.hasOwnProperty.call(msg, specificData)) {
return { ...dataItem, value: msg[specificData] }
}
}
return dataItem
})

store.dispatch(setExtraData(updatedExtraDroneData))
}

// Handle graph messages
// Function to get the graph data from a message
function getGraphDataFromMessage(msg, targetMessageKey) {
const returnDataArray = []
for (let graphKey in storeState.droneInfo.graphs.selectedGraphs) {
const messageKey =
storeState.droneInfo.graphs.selectedGraphs[graphKey]
if (messageKey && messageKey.includes(targetMessageKey)) {
const [, valueName] = messageKey.split(".")

// Applying Data Formatters
let formatted_value = msg[valueName]
if (messageKey in dataFormatters) {
formatted_value = dataFormatters[messageKey](
msg[valueName].toFixed(3),
)
}

returnDataArray.push({
data: { x: Date.now(), y: formatted_value },
graphKey: graphKey,
})
}
}
if (returnDataArray.length) {
return returnDataArray
}
return false
}
store.dispatch(
setLastGraphMessage(
getGraphDataFromMessage(msg, msg.mavpackettype),
),
)

// Handle Flight Mode incoming data
if (
msg.mavpackettype === "RC_CHANNELS" &&
storeState.config.flightModeChannel !== "UNKNOWN"
) {
store.dispatch(
setCurrentPwmValue(
msg[`chan${storeState.config.flightModeChannel}_raw`],
),
)
}
})
}
}

Expand Down Expand Up @@ -871,79 +967,6 @@ const socketMiddleware = (store) => {
}
},
)

/*
Generic Drone Data
*/
socket.socket.on(DroneSpecificSocketEvents.onIncomingMsg, (msg) => {
incomingMessageHandler(msg)

// Data points on dashboard, the below code updates the value in the store when a new message
// comes in in the type of specificData.
const packetType = msg.mavpackettype
const storeState = store.getState()
if (storeState !== undefined) {
const extraDroneData = storeState.droneInfo.extraDroneData
const updatedExtraDroneData = extraDroneData.map((dataItem) => {
if (dataItem.currently_selected.startsWith(packetType)) {
const specificData = dataItem.currently_selected.split(".")[1]
if (Object.prototype.hasOwnProperty.call(msg, specificData)) {
return { ...dataItem, value: msg[specificData] }
}
}
return dataItem
})

store.dispatch(setExtraData(updatedExtraDroneData))
}

// Handle graph messages
// Function to get the graph data from a message
function getGraphDataFromMessage(msg, targetMessageKey) {
const returnDataArray = []
for (let graphKey in storeState.droneInfo.graphs.selectedGraphs) {
const messageKey =
storeState.droneInfo.graphs.selectedGraphs[graphKey]
if (messageKey && messageKey.includes(targetMessageKey)) {
const [, valueName] = messageKey.split(".")

// Applying Data Formatters
let formatted_value = msg[valueName]
if (messageKey in dataFormatters) {
formatted_value = dataFormatters[messageKey](
msg[valueName].toFixed(3),
)
}

returnDataArray.push({
data: { x: Date.now(), y: formatted_value },
graphKey: graphKey,
})
}
}
if (returnDataArray.length) {
return returnDataArray
}
return false
}
store.dispatch(
setLastGraphMessage(
getGraphDataFromMessage(msg, msg.mavpackettype),
),
)

// Handle Flight Mode incoming data
if (
msg.mavpackettype === "RC_CHANNELS" &&
storeState.config.flightModeChannel !== "UNKNOWN"
) {
store.dispatch(
setCurrentPwmValue(
msg[`chan${storeState.config.flightModeChannel}_raw`],
),
)
}
})
} else {
// Turn off socket events
Object.values(DroneSpecificSocketEvents).map((event) =>
Expand All @@ -958,6 +981,9 @@ const socketMiddleware = (store) => {
Object.values(ConfigSpecificSocketEvents).map((event) =>
socket.socket.off(event),
)

// Turn off telemetry socket events
socket.telemetrySocket.off(DroneSpecificSocketEvents.onIncomingMsg)
}
}

Expand Down
5 changes: 5 additions & 0 deletions radio/app/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ def create_app(debug: bool = False) -> Flask:
debug: Boolean value for if the debugging should be True or False
"""
from app.endpoints import endpoints
from app.endpoints.telemetry_namespace import TelemetryNamespace

app = Flask(__name__)
app.debug = debug
Expand All @@ -32,4 +33,8 @@ def create_app(debug: bool = False) -> Flask:

logger.info("Initialising app")
socketio.init_app(app)

# Register telemetry namespace
socketio.on_namespace(TelemetryNamespace("/telemetry"))

return app
73 changes: 50 additions & 23 deletions radio/app/controllers/armController.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
from __future__ import annotations

import time
from threading import current_thread
from typing import TYPE_CHECKING

from app.customTypes import Response
Expand All @@ -19,6 +20,7 @@ def __init__(self, drone: Drone) -> None:
Args:
drone (Drone): The main drone object
"""
self.controller_id = f"arm_{current_thread().ident}"
self.drone = drone

@sendingCommandLock
Expand All @@ -35,17 +37,25 @@ def arm(self, force: bool = False) -> Response:
if self.drone.armed:
return {"success": False, "message": "Already armed"}

self.drone.is_listening = False

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
)
if not self.drone.reserve_message_type("COMMAND_ACK", self.controller_id):
return {
"success": False,
"message": "Could not reserve COMMAND_ACK messages",
}

try:
response = self.drone.master.recv_match(type="COMMAND_ACK", blocking=True)
self.drone.is_listening = True
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
)

response = self.drone.wait_for_message(
"COMMAND_ACK",
self.controller_id,
condition_func=lambda msg: msg.command
== mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
)

if commandAccepted(response, mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM):
# Wait for the drone to be armed fully after the command has been accepted
Expand All @@ -56,13 +66,18 @@ def arm(self, force: bool = False) -> Response:
return {"success": True, "message": "Armed successfully"}
else:
self.drone.logger.debug("Arming failed")
return {
"success": False,
"message": "Could not arm, command not accepted",
}

except Exception as e:
self.drone.is_listening = True
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, command not accepted"}
finally:
self.drone.release_message_type("COMMAND_ACK", self.controller_id)

@sendingCommandLock
def disarm(self, force: bool = False) -> Response:
Expand All @@ -78,17 +93,25 @@ def disarm(self, force: bool = False) -> Response:
if not self.drone.armed:
return {"success": False, "message": "Already disarmed"}

self.drone.is_listening = False

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
)
if not self.drone.reserve_message_type("COMMAND_ACK", self.controller_id):
return {
"success": False,
"message": "Could not reserve COMMAND_ACK messages",
}

try:
response = self.drone.master.recv_match(type="COMMAND_ACK", blocking=True)
self.drone.is_listening = True
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
)

response = self.drone.wait_for_message(
"COMMAND_ACK",
self.controller_id,
condition_func=lambda msg: msg.command
== mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
)

if commandAccepted(response, mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM):
# Wait for the drone to be disarmed fully after the command has been accepted
Expand All @@ -99,11 +122,15 @@ def disarm(self, force: bool = False) -> Response:
return {"success": True, "message": "Disarmed successfully"}
else:
self.drone.logger.debug("Could not disarm, command not accepted")
return {
"success": False,
"message": "Could not disarm, command not accepted",
}

except Exception as e:
self.drone.is_listening = True
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, command not accepted"}
finally:
self.drone.release_message_type("COMMAND_ACK", self.controller_id)
Loading