From fd9bf17cfb2a495f644d1400ae3599b5814aafd3 Mon Sep 17 00:00:00 2001 From: Kush Makkapati Date: Tue, 29 Jul 2025 21:33:03 +0100 Subject: [PATCH 1/5] Make missions items table header sticky --- gcs/src/components/missions/missionItemsTable.jsx | 2 +- gcs/src/components/missions/rallyItemsTable.jsx | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/gcs/src/components/missions/missionItemsTable.jsx b/gcs/src/components/missions/missionItemsTable.jsx index acd7fef14..5667b009d 100644 --- a/gcs/src/components/missions/missionItemsTable.jsx +++ b/gcs/src/components/missions/missionItemsTable.jsx @@ -12,7 +12,7 @@ function MissionItemsTableNonMemo({ updateMissionItem, }) { return ( - +
diff --git a/gcs/src/components/missions/rallyItemsTable.jsx b/gcs/src/components/missions/rallyItemsTable.jsx index d1b73a02d..19398961f 100644 --- a/gcs/src/components/missions/rallyItemsTable.jsx +++ b/gcs/src/components/missions/rallyItemsTable.jsx @@ -7,7 +7,7 @@ import RallyItemsTableRow from "./rallyItemsTableRow" function RallyItemsTableNonMemo({ rallyItems, updateRallyItem }) { return ( -
+
From d50c79f408f9982a4791450d157adaf09aa11e88 Mon Sep 17 00:00:00 2001 From: Kush Makkapati Date: Tue, 29 Jul 2025 22:13:17 +0100 Subject: [PATCH 2/5] Add waypoint deletion and dotted line to join last and first waypoints if no land --- .../components/mapComponents/missionItems.jsx | 29 +++++++++++++++---- .../components/missions/missionItemsTable.jsx | 5 +++- .../missions/missionItemsTableRow.jsx | 18 +++++++++++- .../components/missions/rallyItemsTable.jsx | 2 +- gcs/src/missions.jsx | 13 +++++++++ 5 files changed, 59 insertions(+), 8 deletions(-) diff --git a/gcs/src/components/mapComponents/missionItems.jsx b/gcs/src/components/mapComponents/missionItems.jsx index d624cb3dd..60834ddcc 100644 --- a/gcs/src/components/mapComponents/missionItems.jsx +++ b/gcs/src/components/mapComponents/missionItems.jsx @@ -31,34 +31,47 @@ export default function MissionItems({ filterMissionItems(missionItems), ) const [listOfLineCoords, setListOfLineCoords] = useState([]) + const [listOfDottedLineCoords, setListOfDottedLineCoords] = useState([]) useEffect(() => { setFilteredMissionItems(filterMissionItems(missionItems)) }, [missionItems]) useEffect(() => { - setListOfLineCoords(getListOfLineCoordinates(filteredMissionItems)) + const { solid: solidLineCoords, dotted: dottedLineCoords } = + getListOfLineCoordinates(filteredMissionItems) + + console.log(solidLineCoords) + console.log(dottedLineCoords) + setListOfLineCoords(solidLineCoords) + setListOfDottedLineCoords(dottedLineCoords) }, [filteredMissionItems]) function getListOfLineCoordinates(filteredMissionItems) { - if (filteredMissionItems.length === 0) return [] + if (filteredMissionItems.length === 0) return { solid: [], dotted: [] } const lineCoordsList = [] + const dottedLineCoordsList = [] filteredMissionItems.forEach((item) => { lineCoordsList.push([intToCoord(item.y), intToCoord(item.x)]) }) - // Join the last item to first item if aircraft does not land + // Join the last item to first item if aircraft does not land, with a + // dotted line if ( ![21, 189].includes( filteredMissionItems[filteredMissionItems.length - 1].command, ) ) { - lineCoordsList.push([ + dottedLineCoordsList.push([ intToCoord(filteredMissionItems[0].y), intToCoord(filteredMissionItems[0].x), ]) + dottedLineCoordsList.push([ + intToCoord(filteredMissionItems[filteredMissionItems.length - 1].y), + intToCoord(filteredMissionItems[filteredMissionItems.length - 1].x), + ]) } // Connect jump commands to previously displayed item and jump target item @@ -80,7 +93,7 @@ export default function MissionItems({ lineCoordsList.push([intToCoord(nextItem.y), intToCoord(nextItem.x)]) }) - return lineCoordsList + return { solid: lineCoordsList, dotted: dottedLineCoordsList } } return ( @@ -107,6 +120,12 @@ export default function MissionItems({ coordinates={listOfLineCoords} colour={tailwindColors.yellow[400]} /> + + ) } diff --git a/gcs/src/components/missions/missionItemsTable.jsx b/gcs/src/components/missions/missionItemsTable.jsx index 5667b009d..cb468ab25 100644 --- a/gcs/src/components/missions/missionItemsTable.jsx +++ b/gcs/src/components/missions/missionItemsTable.jsx @@ -10,6 +10,7 @@ function MissionItemsTableNonMemo({ missionItems, aircraftType, updateMissionItem, + deleteMissionItem, }) { return (
@@ -22,9 +23,10 @@ function MissionItemsTableNonMemo({ Param 3Param 4Lat - Long + LngAltFrame + @@ -45,6 +47,7 @@ function MissionItemsTableNonMemo({ aircraftType={aircraftType} missionItem={missionItem} updateMissionItem={updateMissionItem} + deleteMissionItem={deleteMissionItem} /> ) })} diff --git a/gcs/src/components/missions/missionItemsTableRow.jsx b/gcs/src/components/missions/missionItemsTableRow.jsx index 29ae943ec..21637fe72 100644 --- a/gcs/src/components/missions/missionItemsTableRow.jsx +++ b/gcs/src/components/missions/missionItemsTableRow.jsx @@ -2,7 +2,14 @@ This component displays the row for a mission item in a table. */ -import { NumberInput, Select, TableTd, TableTr } from "@mantine/core" +import { + ActionIcon, + NumberInput, + Select, + TableTd, + TableTr, +} from "@mantine/core" +import { IconTrash } from "@tabler/icons-react" import { useEffect, useState } from "react" import { coordToInt, intToCoord } from "../../helpers/dataFormatters" import { @@ -18,6 +25,7 @@ export default function MissionItemsTableRow({ aircraftType, missionItem, updateMissionItem, + deleteMissionItem, }) { const [missionItemData, setMissionItemData] = useState(missionItem) @@ -131,6 +139,14 @@ export default function MissionItemsTableRow({ /> {getFrameName(missionItemData.frame)} + + deleteMissionItem(missionItemData.id)} + color="red" + > + + + ) } diff --git a/gcs/src/components/missions/rallyItemsTable.jsx b/gcs/src/components/missions/rallyItemsTable.jsx index 19398961f..95abf6ba6 100644 --- a/gcs/src/components/missions/rallyItemsTable.jsx +++ b/gcs/src/components/missions/rallyItemsTable.jsx @@ -17,7 +17,7 @@ function RallyItemsTableNonMemo({ rallyItems, updateRallyItem }) { Param 3 Param 4 Lat - Long + Lng Alt Frame diff --git a/gcs/src/missions.jsx b/gcs/src/missions.jsx index 149cd704e..e4035ac59 100644 --- a/gcs/src/missions.jsx +++ b/gcs/src/missions.jsx @@ -187,6 +187,18 @@ export default function Missions() { ) } + function deleteMissionItem(missionItemId) { + setMissionItems((prevItems) => { + const updatedItems = prevItems.filter((item) => item.id !== missionItemId) + + return updatedItems.map((item, index) => ({ + ...item, + seq: index, // Reassign seq based on the new order + })) + }) + console.log(missionItems) + } + function readMissionFromDrone() { socket.emit("get_current_mission", { type: activeTab }) } @@ -350,6 +362,7 @@ export default function Missions() { missionItems={missionItems} aircraftType={aircraftType} updateMissionItem={updateMissionItem} + deleteMissionItem={deleteMissionItem} /> From 4281a06719fe6909f57b604ca3ef02ce1ce9f377 Mon Sep 17 00:00:00 2001 From: Kush Makkapati Date: Wed, 30 Jul 2025 13:12:58 +0100 Subject: [PATCH 3/5] Add increment and decrement controls to mission items --- .../components/mapComponents/missionItems.jsx | 2 -- .../components/missions/missionItemsTable.jsx | 2 ++ .../missions/missionItemsTableRow.jsx | 15 ++++++-- gcs/src/missions.jsx | 36 ++++++++++++++++++- 4 files changed, 50 insertions(+), 5 deletions(-) diff --git a/gcs/src/components/mapComponents/missionItems.jsx b/gcs/src/components/mapComponents/missionItems.jsx index 60834ddcc..3d9ee1b38 100644 --- a/gcs/src/components/mapComponents/missionItems.jsx +++ b/gcs/src/components/mapComponents/missionItems.jsx @@ -41,8 +41,6 @@ export default function MissionItems({ const { solid: solidLineCoords, dotted: dottedLineCoords } = getListOfLineCoordinates(filteredMissionItems) - console.log(solidLineCoords) - console.log(dottedLineCoords) setListOfLineCoords(solidLineCoords) setListOfDottedLineCoords(dottedLineCoords) }, [filteredMissionItems]) diff --git a/gcs/src/components/missions/missionItemsTable.jsx b/gcs/src/components/missions/missionItemsTable.jsx index cb468ab25..1563227a6 100644 --- a/gcs/src/components/missions/missionItemsTable.jsx +++ b/gcs/src/components/missions/missionItemsTable.jsx @@ -11,6 +11,7 @@ function MissionItemsTableNonMemo({ aircraftType, updateMissionItem, deleteMissionItem, + updateMissionItemOrder, }) { return (
@@ -48,6 +49,7 @@ function MissionItemsTableNonMemo({ missionItem={missionItem} updateMissionItem={updateMissionItem} deleteMissionItem={deleteMissionItem} + updateMissionItemOrder={updateMissionItemOrder} /> ) })} diff --git a/gcs/src/components/missions/missionItemsTableRow.jsx b/gcs/src/components/missions/missionItemsTableRow.jsx index 21637fe72..6ac80dee7 100644 --- a/gcs/src/components/missions/missionItemsTableRow.jsx +++ b/gcs/src/components/missions/missionItemsTableRow.jsx @@ -9,7 +9,7 @@ import { TableTd, TableTr, } from "@mantine/core" -import { IconTrash } from "@tabler/icons-react" +import { IconArrowDown, IconArrowUp, IconTrash } from "@tabler/icons-react" import { useEffect, useState } from "react" import { coordToInt, intToCoord } from "../../helpers/dataFormatters" import { @@ -26,6 +26,7 @@ export default function MissionItemsTableRow({ missionItem, updateMissionItem, deleteMissionItem, + updateMissionItemOrder, }) { const [missionItemData, setMissionItemData] = useState(missionItem) @@ -139,7 +140,17 @@ export default function MissionItemsTableRow({ /> {getFrameName(missionItemData.frame)} - + + updateMissionItemOrder(missionItemData.id, -1)} + > + + + updateMissionItemOrder(missionItemData.id, 1)} + > + + deleteMissionItem(missionItemData.id)} color="red" diff --git a/gcs/src/missions.jsx b/gcs/src/missions.jsx index e4035ac59..4c05ac295 100644 --- a/gcs/src/missions.jsx +++ b/gcs/src/missions.jsx @@ -196,7 +196,40 @@ export default function Missions() { seq: index, // Reassign seq based on the new order })) }) - console.log(missionItems) + } + + function updateMissionItemOrder(missionItemId, indexIncrement) { + setMissionItems((prevItems) => { + const currentIndex = prevItems.findIndex( + (item) => item.id === missionItemId, + ) + + // Ensure the item exists and the swap is within bounds + if ( + currentIndex === -1 || + (indexIncrement === -1 && currentIndex === 0) || + (indexIncrement === 1 && currentIndex === prevItems.length - 1) + ) { + return prevItems // No changes if out of bounds + } + + // Calculate the new index + const newIndex = currentIndex + indexIncrement + + // Create a copy of the items array + const updatedItems = [...prevItems] + + // Swap the items + const temp = updatedItems[currentIndex] + updatedItems[currentIndex] = updatedItems[newIndex] + updatedItems[newIndex] = temp + + // Update the seq values + updatedItems[currentIndex].seq = currentIndex + updatedItems[newIndex].seq = newIndex + + return updatedItems + }) } function readMissionFromDrone() { @@ -363,6 +396,7 @@ export default function Missions() { aircraftType={aircraftType} updateMissionItem={updateMissionItem} deleteMissionItem={deleteMissionItem} + updateMissionItemOrder={updateMissionItemOrder} /> From ac936fe4e10619847962d54faaf9a7874cfcdfaa Mon Sep 17 00:00:00 2001 From: Kush Makkapati Date: Wed, 30 Jul 2025 14:42:22 +0100 Subject: [PATCH 4/5] Add click on map to add waypoint --- .../components/mapComponents/missionItems.jsx | 21 ++++++--- gcs/src/components/missions/missionsMap.jsx | 7 +++ gcs/src/missions.jsx | 46 +++++++++++++++++-- radio/app/endpoints/connections.py | 17 +++++++ radio/tests/test_connections.py | 18 +++++++- 5 files changed, 98 insertions(+), 11 deletions(-) diff --git a/gcs/src/components/mapComponents/missionItems.jsx b/gcs/src/components/mapComponents/missionItems.jsx index 3d9ee1b38..d1ad022ef 100644 --- a/gcs/src/components/mapComponents/missionItems.jsx +++ b/gcs/src/components/mapComponents/missionItems.jsx @@ -51,7 +51,16 @@ export default function MissionItems({ const lineCoordsList = [] const dottedLineCoordsList = [] - filteredMissionItems.forEach((item) => { + // Stop processing waypoints after a land command + const landCommandIndex = filteredMissionItems.findIndex((item) => + [21, 189].includes(item.command), + ) + const itemsToProcess = + landCommandIndex === -1 + ? filteredMissionItems + : filteredMissionItems.slice(0, landCommandIndex + 1) + + itemsToProcess.forEach((item) => { lineCoordsList.push([intToCoord(item.y), intToCoord(item.x)]) }) @@ -59,16 +68,16 @@ export default function MissionItems({ // dotted line if ( ![21, 189].includes( - filteredMissionItems[filteredMissionItems.length - 1].command, + itemsToProcess[itemsToProcess.length - 1].command, // Use itemsToProcess here ) ) { dottedLineCoordsList.push([ - intToCoord(filteredMissionItems[0].y), - intToCoord(filteredMissionItems[0].x), + intToCoord(itemsToProcess[0].y), // Use itemsToProcess here + intToCoord(itemsToProcess[0].x), ]) dottedLineCoordsList.push([ - intToCoord(filteredMissionItems[filteredMissionItems.length - 1].y), - intToCoord(filteredMissionItems[filteredMissionItems.length - 1].x), + intToCoord(itemsToProcess[itemsToProcess.length - 1].y), // Use itemsToProcess here + intToCoord(itemsToProcess[itemsToProcess.length - 1].x), ]) } diff --git a/gcs/src/components/missions/missionsMap.jsx b/gcs/src/components/missions/missionsMap.jsx index 523f93331..0a7577505 100644 --- a/gcs/src/components/missions/missionsMap.jsx +++ b/gcs/src/components/missions/missionsMap.jsx @@ -53,6 +53,7 @@ function MapSectionNonMemo({ currentTab, markerDragEndCallback, rallyDragEndCallback, + addNewMissionItem, mapId = "dashboard", }) { const [connected] = useSessionStorage({ @@ -198,6 +199,12 @@ function MapSectionNonMemo({ }, }) }} + onClick={(e) => { + setClicked(false) + let lat = e.lngLat.lat + let lon = e.lngLat.lng + addNewMissionItem(lat, lon) + }} cursor="default" > {/* Show marker on map if the position is set */} diff --git a/gcs/src/missions.jsx b/gcs/src/missions.jsx index 4c05ac295..2f3f25278 100644 --- a/gcs/src/missions.jsx +++ b/gcs/src/missions.jsx @@ -17,10 +17,11 @@ import MissionItemsTable from "./components/missions/missionItemsTable" import MissionsMapSection from "./components/missions/missionsMap" import RallyItemsTable from "./components/missions/rallyItemsTable" import NoDroneConnected from "./components/noDroneConnected" -import { intToCoord } from "./helpers/dataFormatters" +import { coordToInt, intToCoord } from "./helpers/dataFormatters" import { COPTER_MODES_FLIGHT_MODE_MAP, MAV_AUTOPILOT_INVALID, + MAV_FRAME_LIST, PLANE_MODES_FLIGHT_MODE_MAP, } from "./helpers/mavlinkConstants" import { @@ -60,6 +61,12 @@ export default function Missions() { key: "homePosition", defaultValue: null, }) + const [targetInfo, setTargetInfo] = useSessionStorage({ + key: "targetInfo", + defaultValue: { target_component: 0, target_system: 255 }, + }) + + const newMissionItemAltitude = 30 // Heartbeat data const [heartbeatData, setHeartbeatData] = useState({ system_status: 0 }) @@ -92,6 +99,7 @@ export default function Missions() { } else { socket.emit("set_state", { state: "missions" }) socket.emit("get_home_position") + socket.emit("get_target_info") } socket.on("incoming_msg", (msg) => { @@ -108,14 +116,18 @@ export default function Missions() { } }) + socket.on("target_info", (data) => { + if (data) { + setTargetInfo(data) + } + }) + socket.on("current_mission", (data) => { if (!data.success) { showErrorNotification(data.message) return } - console.log(data) - if (data.mission_type === "mission") { const missionItemsWithIds = [] for (let missionItem of data.items) { @@ -146,6 +158,7 @@ export default function Missions() { return () => { socket.off("incoming_msg") socket.off("home_position_result") + socket.off("target_info") socket.off("current_mission") socket.off("write_mission_result") } @@ -168,6 +181,32 @@ export default function Missions() { return missionItem } + function addNewMissionItem(lat, lon) { + const newMissionItem = { + id: uuidv4(), + seq: missionItems.length, + x: coordToInt(lat), + y: coordToInt(lon), + z: newMissionItemAltitude, + frame: Object.keys(MAV_FRAME_LIST).find( + (key) => MAV_FRAME_LIST[key] === "MAV_FRAME_GLOBAL_RELATIVE_ALT", + ), + command: 16, // MAV_CMD_NAV_WAYPOINT + param1: 0, + param2: 0, + param3: 0, + param4: 0, + current: 0, + autocontinue: 1, + target_component: targetInfo.target_component, + target_system: targetInfo.target_system, + mission_type: 0, + mavpackettype: "MISSION_ITEM_INT", + } + + setMissionItems((prevItems) => [...prevItems, newMissionItem]) + } + function updateMissionItem(updatedMissionItem) { setMissionItems((prevItems) => prevItems.map((item) => @@ -362,6 +401,7 @@ export default function Missions() { currentTab={activeTab} markerDragEndCallback={updateMissionItem} rallyDragEndCallback={updateRallyItem} + addNewMissionItem={addNewMissionItem} mapId="missions" /> diff --git a/radio/app/endpoints/connections.py b/radio/app/endpoints/connections.py index a3ff891bd..9b3fa7b89 100644 --- a/radio/app/endpoints/connections.py +++ b/radio/app/endpoints/connections.py @@ -28,3 +28,20 @@ def isConnectedToDrone() -> None: Handle client asking if we're connected to the drone or not """ socketio.emit("is_connected_to_drone", bool(droneStatus.drone)) + + +@socketio.on("get_target_info") +def getTargetInfo() -> None: + """ + Return the target component and target system + """ + if droneStatus.drone: + socketio.emit( + "target_info", + { + "target_component": droneStatus.drone.target_component, + "target_system": droneStatus.drone.target_system, + }, + ) + else: + socketio.emit("target_info", None) diff --git a/radio/tests/test_connections.py b/radio/tests/test_connections.py index 6ae6aab89..5db228747 100644 --- a/radio/tests/test_connections.py +++ b/radio/tests/test_connections.py @@ -1,7 +1,6 @@ import pytest -from serial.tools.list_ports_common import ListPortInfo - from flask_socketio.test_client import SocketIOTestClient +from serial.tools.list_ports_common import ListPortInfo from . import falcon_test @@ -12,6 +11,7 @@ def run_once_after_all_tests(): Saves the valid connection string then ensures that the drone connection is established again after the tests have run """ from app import droneStatus + from .conftest import setupDrone assert droneStatus.drone is not None @@ -49,6 +49,20 @@ def test_isConnectedToDrone_with_drone( assert socketio_result[0]["name"] == "is_connected_to_drone" # Correct name emitted +@falcon_test(pass_drone_status=True) +def test_getTargetInfo(socketio_client: SocketIOTestClient, droneStatus): + socketio_client.emit("get_target_info") + socketio_result = socketio_client.get_received() + + assert len(socketio_result) == 1 + assert socketio_result[0]["name"] == "target_info" + assert socketio_result[0]["args"][0] == { + "target_component": 0, + "target_system": 1, + } + + +# Has to be the final test otherwise the socket disconnects @falcon_test(pass_drone_status=True) def test_disconnect(socketio_client: SocketIOTestClient, droneStatus): """Test disconnecting from socket""" From 3b7b7800bf4b027facd0533670a9231ac2265d87 Mon Sep 17 00:00:00 2001 From: Kush Makkapati Date: Wed, 30 Jul 2025 15:07:26 +0100 Subject: [PATCH 5/5] Bug fix new mission frame being a string --- gcs/src/missions.jsx | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/gcs/src/missions.jsx b/gcs/src/missions.jsx index 2f3f25278..1b6f57b3f 100644 --- a/gcs/src/missions.jsx +++ b/gcs/src/missions.jsx @@ -66,7 +66,7 @@ export default function Missions() { defaultValue: { target_component: 0, target_system: 255 }, }) - const newMissionItemAltitude = 30 + const newMissionItemAltitude = 30 // TODO: Make this configurable // Heartbeat data const [heartbeatData, setHeartbeatData] = useState({ system_status: 0 }) @@ -188,8 +188,10 @@ export default function Missions() { x: coordToInt(lat), y: coordToInt(lon), z: newMissionItemAltitude, - frame: Object.keys(MAV_FRAME_LIST).find( - (key) => MAV_FRAME_LIST[key] === "MAV_FRAME_GLOBAL_RELATIVE_ALT", + frame: parseInt( + Object.keys(MAV_FRAME_LIST).find( + (key) => MAV_FRAME_LIST[key] === "MAV_FRAME_GLOBAL_RELATIVE_ALT", + ), ), command: 16, // MAV_CMD_NAV_WAYPOINT param1: 0,