Skip to content

Commit 3db6a3f

Browse files
committed
alpha-0.1.10/575-add-improvements-to-mission-items-on-missions-page (#591)
* Make missions items table header sticky * Add waypoint deletion and dotted line to join last and first waypoints if no land * Add increment and decrement controls to mission items * Add click on map to add waypoint * Bug fix new mission frame being a string
1 parent 0ae1b84 commit 3db6a3f

8 files changed

Lines changed: 205 additions & 20 deletions

File tree

gcs/src/components/mapComponents/missionItems.jsx

Lines changed: 36 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -31,33 +31,53 @@ export default function MissionItems({
3131
filterMissionItems(missionItems),
3232
)
3333
const [listOfLineCoords, setListOfLineCoords] = useState([])
34+
const [listOfDottedLineCoords, setListOfDottedLineCoords] = useState([])
3435

3536
useEffect(() => {
3637
setFilteredMissionItems(filterMissionItems(missionItems))
3738
}, [missionItems])
3839

3940
useEffect(() => {
40-
setListOfLineCoords(getListOfLineCoordinates(filteredMissionItems))
41+
const { solid: solidLineCoords, dotted: dottedLineCoords } =
42+
getListOfLineCoordinates(filteredMissionItems)
43+
44+
setListOfLineCoords(solidLineCoords)
45+
setListOfDottedLineCoords(dottedLineCoords)
4146
}, [filteredMissionItems])
4247

4348
function getListOfLineCoordinates(filteredMissionItems) {
44-
if (filteredMissionItems.length === 0) return []
49+
if (filteredMissionItems.length === 0) return { solid: [], dotted: [] }
4550

4651
const lineCoordsList = []
47-
48-
filteredMissionItems.forEach((item) => {
52+
const dottedLineCoordsList = []
53+
54+
// Stop processing waypoints after a land command
55+
const landCommandIndex = filteredMissionItems.findIndex((item) =>
56+
[21, 189].includes(item.command),
57+
)
58+
const itemsToProcess =
59+
landCommandIndex === -1
60+
? filteredMissionItems
61+
: filteredMissionItems.slice(0, landCommandIndex + 1)
62+
63+
itemsToProcess.forEach((item) => {
4964
lineCoordsList.push([intToCoord(item.y), intToCoord(item.x)])
5065
})
5166

52-
// Join the last item to first item if aircraft does not land
67+
// Join the last item to first item if aircraft does not land, with a
68+
// dotted line
5369
if (
5470
![21, 189].includes(
55-
filteredMissionItems[filteredMissionItems.length - 1].command,
71+
itemsToProcess[itemsToProcess.length - 1].command, // Use itemsToProcess here
5672
)
5773
) {
58-
lineCoordsList.push([
59-
intToCoord(filteredMissionItems[0].y),
60-
intToCoord(filteredMissionItems[0].x),
74+
dottedLineCoordsList.push([
75+
intToCoord(itemsToProcess[0].y), // Use itemsToProcess here
76+
intToCoord(itemsToProcess[0].x),
77+
])
78+
dottedLineCoordsList.push([
79+
intToCoord(itemsToProcess[itemsToProcess.length - 1].y), // Use itemsToProcess here
80+
intToCoord(itemsToProcess[itemsToProcess.length - 1].x),
6181
])
6282
}
6383

@@ -80,7 +100,7 @@ export default function MissionItems({
80100
lineCoordsList.push([intToCoord(nextItem.y), intToCoord(nextItem.x)])
81101
})
82102

83-
return lineCoordsList
103+
return { solid: lineCoordsList, dotted: dottedLineCoordsList }
84104
}
85105

86106
return (
@@ -107,6 +127,12 @@ export default function MissionItems({
107127
coordinates={listOfLineCoords}
108128
colour={tailwindColors.yellow[400]}
109129
/>
130+
131+
<DrawLineCoordinates
132+
coordinates={listOfDottedLineCoords}
133+
colour={tailwindColors.yellow[400]}
134+
lineProps={{ "line-dasharray": [2, 2] }}
135+
/>
110136
</>
111137
)
112138
}

gcs/src/components/missions/missionItemsTable.jsx

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,9 +10,11 @@ function MissionItemsTableNonMemo({
1010
missionItems,
1111
aircraftType,
1212
updateMissionItem,
13+
deleteMissionItem,
14+
updateMissionItemOrder,
1315
}) {
1416
return (
15-
<Table striped withTableBorder withColumnBorders>
17+
<Table striped withTableBorder withColumnBorders stickyHeader>
1618
<Table.Thead>
1719
<Table.Tr>
1820
<Table.Th></Table.Th>
@@ -22,9 +24,10 @@ function MissionItemsTableNonMemo({
2224
<Table.Th>Param 3</Table.Th>
2325
<Table.Th>Param 4</Table.Th>
2426
<Table.Th>Lat</Table.Th>
25-
<Table.Th>Long</Table.Th>
27+
<Table.Th>Lng</Table.Th>
2628
<Table.Th>Alt</Table.Th>
2729
<Table.Th>Frame</Table.Th>
30+
<Table.Th></Table.Th>
2831
</Table.Tr>
2932
</Table.Thead>
3033
<Table.Tbody>
@@ -45,6 +48,8 @@ function MissionItemsTableNonMemo({
4548
aircraftType={aircraftType}
4649
missionItem={missionItem}
4750
updateMissionItem={updateMissionItem}
51+
deleteMissionItem={deleteMissionItem}
52+
updateMissionItemOrder={updateMissionItemOrder}
4853
/>
4954
)
5055
})}

gcs/src/components/missions/missionItemsTableRow.jsx

Lines changed: 28 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,14 @@
22
This component displays the row for a mission item in a table.
33
*/
44

5-
import { NumberInput, Select, TableTd, TableTr } from "@mantine/core"
5+
import {
6+
ActionIcon,
7+
NumberInput,
8+
Select,
9+
TableTd,
10+
TableTr,
11+
} from "@mantine/core"
12+
import { IconArrowDown, IconArrowUp, IconTrash } from "@tabler/icons-react"
613
import { useEffect, useState } from "react"
714
import { coordToInt, intToCoord } from "../../helpers/dataFormatters"
815
import {
@@ -18,6 +25,8 @@ export default function MissionItemsTableRow({
1825
aircraftType,
1926
missionItem,
2027
updateMissionItem,
28+
deleteMissionItem,
29+
updateMissionItemOrder,
2130
}) {
2231
const [missionItemData, setMissionItemData] = useState(missionItem)
2332

@@ -131,6 +140,24 @@ export default function MissionItemsTableRow({
131140
/>
132141
</TableTd>
133142
<TableTd>{getFrameName(missionItemData.frame)}</TableTd>
143+
<TableTd className="flex flex-row gap-2">
144+
<ActionIcon
145+
onClick={() => updateMissionItemOrder(missionItemData.id, -1)}
146+
>
147+
<IconArrowUp size={20} />
148+
</ActionIcon>
149+
<ActionIcon
150+
onClick={() => updateMissionItemOrder(missionItemData.id, 1)}
151+
>
152+
<IconArrowDown size={20} />
153+
</ActionIcon>
154+
<ActionIcon
155+
onClick={() => deleteMissionItem(missionItemData.id)}
156+
color="red"
157+
>
158+
<IconTrash size={20} />
159+
</ActionIcon>
160+
</TableTd>
134161
</TableTr>
135162
)
136163
}

gcs/src/components/missions/missionsMap.jsx

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,7 @@ function MapSectionNonMemo({
5353
currentTab,
5454
markerDragEndCallback,
5555
rallyDragEndCallback,
56+
addNewMissionItem,
5657
mapId = "dashboard",
5758
}) {
5859
const [connected] = useSessionStorage({
@@ -198,6 +199,12 @@ function MapSectionNonMemo({
198199
},
199200
})
200201
}}
202+
onClick={(e) => {
203+
setClicked(false)
204+
let lat = e.lngLat.lat
205+
let lon = e.lngLat.lng
206+
addNewMissionItem(lat, lon)
207+
}}
201208
cursor="default"
202209
>
203210
{/* Show marker on map if the position is set */}

gcs/src/components/missions/rallyItemsTable.jsx

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ import RallyItemsTableRow from "./rallyItemsTableRow"
77

88
function RallyItemsTableNonMemo({ rallyItems, updateRallyItem }) {
99
return (
10-
<Table striped withTableBorder withColumnBorders>
10+
<Table striped withTableBorder withColumnBorders stickyHeader>
1111
<Table.Thead>
1212
<Table.Tr>
1313
<Table.Th></Table.Th>
@@ -17,7 +17,7 @@ function RallyItemsTableNonMemo({ rallyItems, updateRallyItem }) {
1717
<Table.Th>Param 3</Table.Th>
1818
<Table.Th>Param 4</Table.Th>
1919
<Table.Th>Lat</Table.Th>
20-
<Table.Th>Long</Table.Th>
20+
<Table.Th>Lng</Table.Th>
2121
<Table.Th>Alt</Table.Th>
2222
<Table.Th>Frame</Table.Th>
2323
</Table.Tr>

gcs/src/missions.jsx

Lines changed: 92 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -17,10 +17,11 @@ import MissionItemsTable from "./components/missions/missionItemsTable"
1717
import MissionsMapSection from "./components/missions/missionsMap"
1818
import RallyItemsTable from "./components/missions/rallyItemsTable"
1919
import NoDroneConnected from "./components/noDroneConnected"
20-
import { intToCoord } from "./helpers/dataFormatters"
20+
import { coordToInt, intToCoord } from "./helpers/dataFormatters"
2121
import {
2222
COPTER_MODES_FLIGHT_MODE_MAP,
2323
MAV_AUTOPILOT_INVALID,
24+
MAV_FRAME_LIST,
2425
PLANE_MODES_FLIGHT_MODE_MAP,
2526
} from "./helpers/mavlinkConstants"
2627
import {
@@ -60,6 +61,12 @@ export default function Missions() {
6061
key: "homePosition",
6162
defaultValue: null,
6263
})
64+
const [targetInfo, setTargetInfo] = useSessionStorage({
65+
key: "targetInfo",
66+
defaultValue: { target_component: 0, target_system: 255 },
67+
})
68+
69+
const newMissionItemAltitude = 30 // TODO: Make this configurable
6370

6471
// Heartbeat data
6572
const [heartbeatData, setHeartbeatData] = useState({ system_status: 0 })
@@ -92,6 +99,7 @@ export default function Missions() {
9299
} else {
93100
socket.emit("set_state", { state: "missions" })
94101
socket.emit("get_home_position")
102+
socket.emit("get_target_info")
95103
}
96104

97105
socket.on("incoming_msg", (msg) => {
@@ -108,14 +116,18 @@ export default function Missions() {
108116
}
109117
})
110118

119+
socket.on("target_info", (data) => {
120+
if (data) {
121+
setTargetInfo(data)
122+
}
123+
})
124+
111125
socket.on("current_mission", (data) => {
112126
if (!data.success) {
113127
showErrorNotification(data.message)
114128
return
115129
}
116130

117-
console.log(data)
118-
119131
if (data.mission_type === "mission") {
120132
const missionItemsWithIds = []
121133
for (let missionItem of data.items) {
@@ -146,6 +158,7 @@ export default function Missions() {
146158
return () => {
147159
socket.off("incoming_msg")
148160
socket.off("home_position_result")
161+
socket.off("target_info")
149162
socket.off("current_mission")
150163
socket.off("write_mission_result")
151164
}
@@ -168,6 +181,34 @@ export default function Missions() {
168181
return missionItem
169182
}
170183

184+
function addNewMissionItem(lat, lon) {
185+
const newMissionItem = {
186+
id: uuidv4(),
187+
seq: missionItems.length,
188+
x: coordToInt(lat),
189+
y: coordToInt(lon),
190+
z: newMissionItemAltitude,
191+
frame: parseInt(
192+
Object.keys(MAV_FRAME_LIST).find(
193+
(key) => MAV_FRAME_LIST[key] === "MAV_FRAME_GLOBAL_RELATIVE_ALT",
194+
),
195+
),
196+
command: 16, // MAV_CMD_NAV_WAYPOINT
197+
param1: 0,
198+
param2: 0,
199+
param3: 0,
200+
param4: 0,
201+
current: 0,
202+
autocontinue: 1,
203+
target_component: targetInfo.target_component,
204+
target_system: targetInfo.target_system,
205+
mission_type: 0,
206+
mavpackettype: "MISSION_ITEM_INT",
207+
}
208+
209+
setMissionItems((prevItems) => [...prevItems, newMissionItem])
210+
}
211+
171212
function updateMissionItem(updatedMissionItem) {
172213
setMissionItems((prevItems) =>
173214
prevItems.map((item) =>
@@ -187,6 +228,51 @@ export default function Missions() {
187228
)
188229
}
189230

231+
function deleteMissionItem(missionItemId) {
232+
setMissionItems((prevItems) => {
233+
const updatedItems = prevItems.filter((item) => item.id !== missionItemId)
234+
235+
return updatedItems.map((item, index) => ({
236+
...item,
237+
seq: index, // Reassign seq based on the new order
238+
}))
239+
})
240+
}
241+
242+
function updateMissionItemOrder(missionItemId, indexIncrement) {
243+
setMissionItems((prevItems) => {
244+
const currentIndex = prevItems.findIndex(
245+
(item) => item.id === missionItemId,
246+
)
247+
248+
// Ensure the item exists and the swap is within bounds
249+
if (
250+
currentIndex === -1 ||
251+
(indexIncrement === -1 && currentIndex === 0) ||
252+
(indexIncrement === 1 && currentIndex === prevItems.length - 1)
253+
) {
254+
return prevItems // No changes if out of bounds
255+
}
256+
257+
// Calculate the new index
258+
const newIndex = currentIndex + indexIncrement
259+
260+
// Create a copy of the items array
261+
const updatedItems = [...prevItems]
262+
263+
// Swap the items
264+
const temp = updatedItems[currentIndex]
265+
updatedItems[currentIndex] = updatedItems[newIndex]
266+
updatedItems[newIndex] = temp
267+
268+
// Update the seq values
269+
updatedItems[currentIndex].seq = currentIndex
270+
updatedItems[newIndex].seq = newIndex
271+
272+
return updatedItems
273+
})
274+
}
275+
190276
function readMissionFromDrone() {
191277
socket.emit("get_current_mission", { type: activeTab })
192278
}
@@ -317,6 +403,7 @@ export default function Missions() {
317403
currentTab={activeTab}
318404
markerDragEndCallback={updateMissionItem}
319405
rallyDragEndCallback={updateRallyItem}
406+
addNewMissionItem={addNewMissionItem}
320407
mapId="missions"
321408
/>
322409
</div>
@@ -350,6 +437,8 @@ export default function Missions() {
350437
missionItems={missionItems}
351438
aircraftType={aircraftType}
352439
updateMissionItem={updateMissionItem}
440+
deleteMissionItem={deleteMissionItem}
441+
updateMissionItemOrder={updateMissionItemOrder}
353442
/>
354443
</Tabs.Panel>
355444
<Tabs.Panel value="fence"></Tabs.Panel>

radio/app/endpoints/connections.py

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,3 +28,20 @@ def isConnectedToDrone() -> None:
2828
Handle client asking if we're connected to the drone or not
2929
"""
3030
socketio.emit("is_connected_to_drone", bool(droneStatus.drone))
31+
32+
33+
@socketio.on("get_target_info")
34+
def getTargetInfo() -> None:
35+
"""
36+
Return the target component and target system
37+
"""
38+
if droneStatus.drone:
39+
socketio.emit(
40+
"target_info",
41+
{
42+
"target_component": droneStatus.drone.target_component,
43+
"target_system": droneStatus.drone.target_system,
44+
},
45+
)
46+
else:
47+
socketio.emit("target_info", None)

0 commit comments

Comments
 (0)