From a55a72dad487977a794be68acf44334950aa22e5 Mon Sep 17 00:00:00 2001 From: Kush Makkapati Date: Thu, 23 Apr 2026 21:00:32 +0100 Subject: [PATCH 1/2] Add insert waypoint button between mission items --- .../components/mapComponents/fenceItems.jsx | 143 +++++++++++++----- .../mapComponents/midpointInsertButton.jsx | 40 +++++ .../components/mapComponents/missionItems.jsx | 87 ++++++++++- .../missions/fenceItemsTableRow.jsx | 33 +++- .../missions/missionItemsTableRow.jsx | 60 +++++++- .../missions/rallyItemsTableRow.jsx | 27 +++- gcs/src/redux/slices/missionSlice.js | 95 ++++++++++++ 7 files changed, 431 insertions(+), 54 deletions(-) create mode 100644 gcs/src/components/mapComponents/midpointInsertButton.jsx diff --git a/gcs/src/components/mapComponents/fenceItems.jsx b/gcs/src/components/mapComponents/fenceItems.jsx index 0b3106fb8..b1878ddcb 100644 --- a/gcs/src/components/mapComponents/fenceItems.jsx +++ b/gcs/src/components/mapComponents/fenceItems.jsx @@ -5,10 +5,10 @@ connecting them. It properly parses the type of fence marker. */ -import { useEffect, useState } from "react" +import { useMemo } from "react" // Helper imports -import { intToCoord } from "../../helpers/dataFormatters" +import { coordToInt, intToCoord } from "../../helpers/dataFormatters" // Styling imports import "maplibre-gl/dist/maplibre-gl.css" @@ -16,16 +16,20 @@ import "maplibre-gl/dist/maplibre-gl.css" // Component imports // Tailwind styling -import { circle } from "@turf/turf" +import { circle, midpoint, point } from "@turf/turf" import { Layer, Source } from "react-map-gl" -import { useSelector } from "react-redux" +import { useDispatch, useSelector } from "react-redux" import resolveConfig from "tailwindcss/resolveConfig" import tailwindConfig from "../../../tailwind.config" import { FENCE_ITEM_COMMANDS_LIST } from "../../helpers/mavlinkConstants" import { selectCurrentPage } from "../../redux/slices/droneConnectionSlice" -import { selectActiveTab } from "../../redux/slices/missionSlice" +import { + insertFencePolygonVertex, + selectActiveTab, +} from "../../redux/slices/missionSlice" import DrawLineCoordinates from "./drawLineCoordinates" import MarkerPin from "./markerPin" +import MidpointInsertButton from "./midpointInsertButton" const tailwindColors = resolveConfig(tailwindConfig).theme.colors function getFenceCommandNumber(value) { @@ -46,25 +50,79 @@ const circleCommands = [ ] export default function FenceItems({ fenceItems }) { + const dispatch = useDispatch() const currentPage = useSelector(selectCurrentPage) const editable = useSelector(selectActiveTab) === "fence" && currentPage === "missions" - const [fencePolygonItems, setFencePolygonItems] = useState([]) - const [fenceCircleItems, setFenceCircleItems] = useState([]) + const { fencePolygonGroups, fencePolygonItems, fenceCircleItems } = + useMemo(() => { + const polygonItems = [] + const circleItems = [] + const polygonGroups = [] - useEffect(() => { - // Filter out fence items based on their type - const polygonItems = fenceItems.filter((item) => - polygonCommands.includes(item.command), - ) - const circleItems = fenceItems.filter((item) => - circleCommands.includes(item.command), - ) + let currentGroup = [] + let currentGroupStartIndex = null - setFencePolygonItems(polygonItems) - setFenceCircleItems(circleItems) - }, [fenceItems]) + fenceItems.forEach((item, index) => { + if (polygonCommands.includes(item.command)) { + const polygonItem = { ...item, fenceIndex: index } + polygonItems.push(polygonItem) + + if (currentGroup.length === 0) { + currentGroupStartIndex = index + } + + currentGroup.push(polygonItem) + + if (currentGroup.length === item.param1) { + polygonGroups.push({ + items: currentGroup, + startIndex: currentGroupStartIndex, + }) + currentGroup = [] + currentGroupStartIndex = null + } + + return + } + + if (circleCommands.includes(item.command)) { + circleItems.push({ ...item, fenceIndex: index }) + } + }) + + return { + fencePolygonGroups: polygonGroups, + fencePolygonItems: polygonItems, + fenceCircleItems: circleItems, + } + }, [fenceItems]) + + const polygonEdgeInsertButtons = useMemo(() => { + if (!editable) return [] + + return fencePolygonGroups.flatMap((polygon) => { + if (polygon.items.length < 2) return [] + + return polygon.items.map((item, index) => { + const nextItem = polygon.items[(index + 1) % polygon.items.length] + const midpointCoords = midpoint( + point([intToCoord(item.y), intToCoord(item.x)]), + point([intToCoord(nextItem.y), intToCoord(nextItem.x)]), + ).geometry.coordinates + + return { + afterId: item.id, + polygonStartIndex: polygon.startIndex, + polygonLength: polygon.items.length, + lat: midpointCoords[1], + lon: midpointCoords[0], + tooltipText: `Insert vertex between ${item.z + 1} and ${nextItem.z + 1}`, + } + }) + }) + }, [editable, fencePolygonGroups]) return ( <> @@ -72,7 +130,7 @@ export default function FenceItems({ fenceItems }) { {fencePolygonItems.map((item, index) => { return ( ( + { + dispatch( + insertFencePolygonVertex({ + afterId: button.afterId, + polygonStartIndex: button.polygonStartIndex, + polygonLength: button.polygonLength, + x: coordToInt(button.lat), + y: coordToInt(button.lon), + }), + ) + }} + /> + ))} + {/* Group fencePolygonItems into separate polygons */} {(() => { - const polygons = [] - let currentPolygon = [] - let currentPoints = 0 - - fencePolygonItems.forEach((item) => { - currentPolygon.push(item) - currentPoints++ - - if (currentPoints === item.param1) { - polygons.push(currentPolygon) - currentPolygon = [] - currentPoints = 0 - } - }) - - return polygons.map((polygon, index) => { - const lastPolygonItem = polygon[polygon.length - 1] + return fencePolygonGroups.map((polygon, index) => { + const lastPolygonItem = polygon.items[polygon.items.length - 1] const color = lastPolygonItem.command === 5002 @@ -111,11 +175,14 @@ export default function FenceItems({ fenceItems }) { [ + ...polygon.items.map((item) => [ intToCoord(item.y), intToCoord(item.x), ]), - [intToCoord(polygon[0].y), intToCoord(polygon[0].x)], + [ + intToCoord(polygon.items[0].y), + intToCoord(polygon.items[0].x), + ], ]} colour={color} lineProps={{ "line-width": 2, "line-dasharray": [4, 6] }} diff --git a/gcs/src/components/mapComponents/midpointInsertButton.jsx b/gcs/src/components/mapComponents/midpointInsertButton.jsx new file mode 100644 index 000000000..85a701527 --- /dev/null +++ b/gcs/src/components/mapComponents/midpointInsertButton.jsx @@ -0,0 +1,40 @@ +/* + A small button rendered at a map midpoint for inserting a new point. +*/ + +import { Marker } from "react-map-gl" + +export default function MidpointInsertButton({ + lat, + lon, + colour, + tooltipText, + onClick, +}) { + return ( + +
{ + e.preventDefault() + e.stopPropagation() + }} + onClick={(e) => { + e.preventDefault() + e.stopPropagation() + onClick?.() + }} + className="pointer-events-auto" + > + +
+
+ ) +} diff --git a/gcs/src/components/mapComponents/missionItems.jsx b/gcs/src/components/mapComponents/missionItems.jsx index b358fe62a..b0a5e2128 100644 --- a/gcs/src/components/mapComponents/missionItems.jsx +++ b/gcs/src/components/mapComponents/missionItems.jsx @@ -5,16 +5,17 @@ connecting them. */ import { useMemo } from "react" -import { useSelector } from "react-redux" +import { useDispatch, useSelector } from "react-redux" import { selectCurrentPage } from "../../redux/slices/droneConnectionSlice" import { selectHomePosition } from "../../redux/slices/droneInfoSlice" import { + insertDrawingItemAfter, selectActiveTab, selectPlannedHomePosition, } from "../../redux/slices/missionSlice" // Helper imports -import { intToCoord } from "../../helpers/dataFormatters" +import { coordToInt, intToCoord } from "../../helpers/dataFormatters" import { filterMissionItems } from "../../helpers/filterMissions" // Styling imports @@ -23,14 +24,17 @@ import "maplibre-gl/dist/maplibre-gl.css" // Component imports import DrawLineCoordinates from "./drawLineCoordinates" import MarkerPin from "./markerPin" +import MidpointInsertButton from "./midpointInsertButton" // Tailwind styling +import { midpoint, point } from "@turf/turf" import resolveConfig from "tailwindcss/resolveConfig" import tailwindConfig from "../../../tailwind.config" const tailwindColors = resolveConfig(tailwindConfig).theme.colors export default function MissionItems({ missionItems }) { + const dispatch = useDispatch() const currentPage = useSelector(selectCurrentPage) const editable = useSelector(selectActiveTab) === "mission" && currentPage === "missions" @@ -49,6 +53,19 @@ export default function MissionItems({ missionItems }) { [filteredMissionItems], ) + const missionPathItems = useMemo(() => { + if (filteredMissionItems.length === 0) return [] + + const stopCommandItem = [...missionItems] + .filter((item) => [20, 21, 189].includes(item.command)) + .sort((a, b) => a.seq - b.seq) + .at(0) + + return stopCommandItem + ? filteredMissionItems.filter((item) => item.seq <= stopCommandItem.seq) + : filteredMissionItems + }, [filteredMissionItems, missionItems]) + const takeoffWaypoint = useMemo(() => { return missionItems.find((item) => item.command === 22) }, [missionItems]) @@ -58,6 +75,40 @@ export default function MissionItems({ missionItems }) { [filteredMissionItems, homePosition, takeoffWaypoint], ) + const insertionMidpoints = useMemo(() => { + if (!editable || missionPathItems.length < 2) return [] + + return missionPathItems + .slice(0, -1) + .map((startItem, index) => { + const endItem = missionPathItems[index + 1] + + const hasHiddenMissionItemsBetween = missionItems.some((item) => { + if (item.seq <= startItem.seq || item.seq >= endItem.seq) { + return false + } + + const itemIsRenderedOnMap = + item.x !== 0 && item.y !== 0 && item.command !== 20 + return !itemIsRenderedOnMap + }) + + if (hasHiddenMissionItemsBetween) { + return null + } + + const midpointCoords = getMidpointCoordinates(startItem, endItem) + + return { + afterId: startItem.id, + lat: midpointCoords[1], + lon: midpointCoords[0], + tooltipText: `Insert waypoint between ${startItem.seq} and ${endItem.seq}`, + } + }) + .filter(Boolean) + }, [editable, missionPathItems]) + function getListOfLineCoordinates(filteredMissionItems) { if (filteredMissionItems.length === 0) return { solid: [], dotted: [] } @@ -152,6 +203,13 @@ export default function MissionItems({ missionItems }) { return { solid: lineCoordsList, dotted: dottedLineSegmentsList } } + function getMidpointCoordinates(startItem, endItem) { + return midpoint( + point([intToCoord(startItem.y), intToCoord(startItem.x)]), + point([intToCoord(endItem.y), intToCoord(endItem.x)]), + ).geometry.coordinates + } + return ( <> {/* Show mission item LABELS */} @@ -170,6 +228,31 @@ export default function MissionItems({ missionItems }) { ) })} + {insertionMidpoints.map((midpointItem) => ( + { + const afterItem = missionPathItems.find( + (item) => item.id === midpointItem.afterId, + ) + + if (!afterItem) return + + dispatch( + insertDrawingItemAfter({ + afterId: afterItem.id, + x: coordToInt(midpointItem.lat), + y: coordToInt(midpointItem.lon), + }), + ) + }} + /> + ))} + {/* Show mission item outlines */} updateFenceItemData("param1", val)} + onChange={(val) => { + const numericValue = parseNumericInput(val) + if (numericValue === null) return + updateFenceItemData("param1", numericValue) + }} hideControls /> @@ -89,21 +102,33 @@ export default function FenceItemsTableRow({ fenceItemIndex }) { updateFenceItemData("x", coordToInt(val))} + onChange={(val) => { + const numericValue = parseNumericInput(val) + if (numericValue === null) return + updateFenceItemData("x", coordToInt(numericValue)) + }} hideControls /> updateFenceItemData("y", coordToInt(val))} + onChange={(val) => { + const numericValue = parseNumericInput(val) + if (numericValue === null) return + updateFenceItemData("y", coordToInt(numericValue)) + }} hideControls /> updateFenceItemData("z", val)} + onChange={(val) => { + const numericValue = parseNumericInput(val) + if (numericValue === null) return + updateFenceItemData("z", numericValue) + }} hideControls /> diff --git a/gcs/src/components/missions/missionItemsTableRow.jsx b/gcs/src/components/missions/missionItemsTableRow.jsx index 505857ce6..91ce408b5 100644 --- a/gcs/src/components/missions/missionItemsTableRow.jsx +++ b/gcs/src/components/missions/missionItemsTableRow.jsx @@ -38,6 +38,24 @@ function formatMetric(value, suffix) { return `${value.toFixed(2)}${suffix}` } +function parseNumericInput(value) { + if (value === null || value === undefined || value === "") { + return null + } + + const numericValue = typeof value === "number" ? value : Number(value) + return Number.isFinite(numericValue) ? numericValue : null +} + +function parseCoordinateInput(value) { + if (value === null || value === undefined || value === "") { + return 0 + } + + const numericValue = parseNumericInput(value) + return numericValue === null ? 0 : numericValue +} + export default function MissionItemsTableRow({ missionItemIndex, rowMetrics }) { const dispatch = useDispatch() const aircraftType = useSelector(selectAircraftType) @@ -128,49 +146,77 @@ export default function MissionItemsTableRow({ missionItemIndex, rowMetrics }) { updateMissionItemData("param1", val)} + onChange={(val) => { + const numericValue = parseNumericInput(val) + if (numericValue === null) return + updateMissionItemData("param1", numericValue) + }} hideControls /> updateMissionItemData("param2", val)} + onChange={(val) => { + const numericValue = parseNumericInput(val) + if (numericValue === null) return + updateMissionItemData("param2", numericValue) + }} hideControls /> updateMissionItemData("param3", val)} + onChange={(val) => { + const numericValue = parseNumericInput(val) + if (numericValue === null) return + updateMissionItemData("param3", numericValue) + }} hideControls /> updateMissionItemData("param4", val)} + onChange={(val) => { + const numericValue = parseNumericInput(val) + if (numericValue === null) return + updateMissionItemData("param4", numericValue) + }} hideControls /> updateMissionItemData("x", coordToInt(val))} + onChange={(val) => { + const numericValue = parseCoordinateInput(val) + if (numericValue === null) return + updateMissionItemData("x", coordToInt(numericValue)) + }} hideControls /> updateMissionItemData("y", coordToInt(val))} + onChange={(val) => { + const numericValue = parseCoordinateInput(val) + if (numericValue === null) return + updateMissionItemData("y", coordToInt(numericValue)) + }} hideControls /> updateMissionItemData("z", val)} + onChange={(val) => { + const numericValue = parseCoordinateInput(val) + if (numericValue === null) return + updateMissionItemData("z", numericValue) + }} hideControls /> diff --git a/gcs/src/components/missions/rallyItemsTableRow.jsx b/gcs/src/components/missions/rallyItemsTableRow.jsx index 223ef1e28..5998b194d 100644 --- a/gcs/src/components/missions/rallyItemsTableRow.jsx +++ b/gcs/src/components/missions/rallyItemsTableRow.jsx @@ -20,6 +20,15 @@ import { } from "../../redux/slices/missionSlice" const coordsFractionDigits = 9 +function parseNumericInput(value) { + if (value === null || value === undefined || value === "") { + return null + } + + const numericValue = typeof value === "number" ? value : Number(value) + return Number.isFinite(numericValue) ? numericValue : null +} + export default function RallyItemsTableRow({ rallyItemIndex }) { const dispatch = useDispatch() const rallyItem = useSelector(selectDrawingRallyItemByIdx(rallyItemIndex)) @@ -59,21 +68,33 @@ export default function RallyItemsTableRow({ rallyItemIndex }) { updateRallyItemData("x", coordToInt(val))} + onChange={(val) => { + const numericValue = parseNumericInput(val) + if (numericValue === null) return + updateRallyItemData("x", coordToInt(numericValue)) + }} hideControls /> updateRallyItemData("y", coordToInt(val))} + onChange={(val) => { + const numericValue = parseNumericInput(val) + if (numericValue === null) return + updateRallyItemData("y", coordToInt(numericValue)) + }} hideControls /> updateRallyItemData("z", val)} + onChange={(val) => { + const numericValue = parseNumericInput(val) + if (numericValue === null) return + updateRallyItemData("z", numericValue) + }} hideControls /> diff --git a/gcs/src/redux/slices/missionSlice.js b/gcs/src/redux/slices/missionSlice.js index 3446364c2..082769fd1 100644 --- a/gcs/src/redux/slices/missionSlice.js +++ b/gcs/src/redux/slices/missionSlice.js @@ -198,6 +198,40 @@ const missionInfoSlice = createSlice({ [state.activeTab]: true, } }, + insertDrawingItemAfter: (state, action) => { + const { afterId, x, y } = action.payload + const _type = `${state.activeTab}Items` + const index = state.drawingItems[_type].findIndex((i) => i.id === afterId) + + if (index === -1) return + + const drawingItem = newMissionItem(x, y, state.targetInfo) + drawingItem.seq = index + 1 + drawingItem.command = { mission: 16, fence: 5004, rally: 5100 }[ + state.activeTab + ] + drawingItem.mission_type = { mission: 0, fence: 1, rally: 2 }[ + state.activeTab + ] + + if (state.activeTab === "fence") { + drawingItem.param1 = 5 + drawingItem.frame = getFrameKey("GLOBAL") + } + + state.drawingItems[_type].splice(index + 1, 0, drawingItem) + state.drawingItems[_type] = state.drawingItems[_type].map( + (item, itemIndex) => ({ + ...item, + seq: itemIndex, + }), + ) + + state.unwrittenChanges = { + ...state.unwrittenChanges, + [state.activeTab]: true, + } + }, reorderDrawingItem: (state, action) => { const { id, increment } = action.payload const _type = `${state.activeTab}Items` @@ -312,6 +346,65 @@ const missionInfoSlice = createSlice({ ] state.unwrittenChanges.fence = true }, + insertFencePolygonVertex: (state, action) => { + const { afterId, polygonStartIndex, polygonLength, x, y } = action.payload + + if ( + typeof polygonStartIndex !== "number" || + typeof polygonLength !== "number" + ) { + return + } + + const fenceItems = state.drawingItems.fenceItems + const index = fenceItems.findIndex((item) => item.id === afterId) + + if (index === -1) return + + const insertIndex = index + 1 + const polygonEndIndex = polygonStartIndex + polygonLength - 1 + + if (index < polygonStartIndex || index > polygonEndIndex) { + return + } + + const polygonItems = fenceItems.slice( + polygonStartIndex, + polygonStartIndex + polygonLength, + ) + + if (polygonItems.length === 0) return + + const fenceTypeCommand = polygonItems[0].command + const drawingItem = { + ...newMissionItem(x, y, state.targetInfo), + command: fenceTypeCommand, + mission_type: 1, + param1: polygonLength + 1, + frame: polygonItems[0].frame, + } + + fenceItems.splice(insertIndex, 0, drawingItem) + + state.drawingItems.fenceItems = fenceItems.map((item, itemIndex) => { + const updatedItem = { + ...item, + seq: itemIndex, + } + + if ( + itemIndex >= polygonStartIndex && + itemIndex <= polygonEndIndex + 1 + ) { + updatedItem.param1 = polygonLength + 1 + updatedItem.z = itemIndex - polygonStartIndex + } + + return updatedItem + }) + + state.unwrittenChanges.fence = true + }, setDrawingMissionItems: (state, action) => { if (action.payload === state.drawingItems.missionItems) return state.drawingItems.missionItems = action.payload @@ -643,11 +736,13 @@ export const { setTargetInfo, updateDrawingItem, removeDrawingItem, + insertDrawingItemAfter, reorderDrawingItem, createNewDefaultDrawingItem, createNewSpecificMissionItem, clearDrawingItems, createFencePolygon, + insertFencePolygonVertex, setDrawingMissionItems, setDrawingFenceItems, setDrawingRallyItems, From 722aa2abd250f57bb3055da3643318d925894624 Mon Sep 17 00:00:00 2001 From: Kush Makkapati Date: Thu, 23 Apr 2026 21:07:02 +0100 Subject: [PATCH 2/2] Address copilot review comments --- gcs/src/components/missions/missionItemsTableRow.jsx | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/gcs/src/components/missions/missionItemsTableRow.jsx b/gcs/src/components/missions/missionItemsTableRow.jsx index 91ce408b5..7e80d04c3 100644 --- a/gcs/src/components/missions/missionItemsTableRow.jsx +++ b/gcs/src/components/missions/missionItemsTableRow.jsx @@ -38,6 +38,7 @@ function formatMetric(value, suffix) { return `${value.toFixed(2)}${suffix}` } +// TODO: Moved into shared helper file function parseNumericInput(value) { if (value === null || value === undefined || value === "") { return null @@ -181,7 +182,6 @@ export default function MissionItemsTableRow({ missionItemIndex, rowMetrics }) { value={missionItem.param4} onChange={(val) => { const numericValue = parseNumericInput(val) - if (numericValue === null) return updateMissionItemData("param4", numericValue) }} hideControls @@ -192,7 +192,6 @@ export default function MissionItemsTableRow({ missionItemIndex, rowMetrics }) { value={intToCoord(missionItem.x).toFixed(coordsFractionDigits)} onChange={(val) => { const numericValue = parseCoordinateInput(val) - if (numericValue === null) return updateMissionItemData("x", coordToInt(numericValue)) }} hideControls @@ -203,7 +202,6 @@ export default function MissionItemsTableRow({ missionItemIndex, rowMetrics }) { value={intToCoord(missionItem.y).toFixed(coordsFractionDigits)} onChange={(val) => { const numericValue = parseCoordinateInput(val) - if (numericValue === null) return updateMissionItemData("y", coordToInt(numericValue)) }} hideControls