Skip to content
Merged
Show file tree
Hide file tree
Changes from 6 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
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
.env
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ IMACS 3.0 is forked from Falcon Ground Control Station (FGCS).

#### Creating a virtual environment

Create a new Python virtual environment using `python -m venv venv`. This can then be activated using `./venv/scripts/activate`.
Create a new Python virtual environment using `python -m venv venv`. This can then be activated using `C`.
Copy link
Collaborator

Choose a reason for hiding this comment

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

You don't need to change this


> NOTE: To enter the virtual environment you will need to run `venv/Scripts/activate` on windows, to learn more please read: [how to make venv for linux and windows](https://www.geeksforgeeks.org/creating-python-virtual-environment-windows-linux/) or [what is a virtual environment?](https://docs.python.org/3/library/venv.html)

Expand Down
46 changes: 46 additions & 0 deletions gcs/src/components/missions/fenceItemsTable.jsx
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
/*
This table displays all the fence items.
*/
import { Table } from "@mantine/core"
import React from "react"
import FenceItemsTableRow from "./fenceItemsTableRow"

function FenceItemsTableNonMemo({ fenceItems, updateFenceItem }) {
return (
<Table striped withTableBorder withColumnBorders>
<Table.Thead>
<Table.Tr>
<Table.Th></Table.Th>
<Table.Th>Command</Table.Th>
<Table.Th>Param 1</Table.Th>
<Table.Th>Param 2</Table.Th>
<Table.Th>Param 3</Table.Th>
<Table.Th>Param 4</Table.Th>
<Table.Th>Lat</Table.Th>
<Table.Th>Long</Table.Th>
<Table.Th>Alt</Table.Th>
<Table.Th>Frame</Table.Th>
</Table.Tr>
</Table.Thead>
<Table.Tbody>
{fenceItems.map((fenceItem, idx) => {
return (
<FenceItemsTableRow
key={fenceItem.id}
index={idx}
fenceItem={fenceItem}
updateFenceItem={updateFenceItem}
/>
)
})}
</Table.Tbody>
</Table>
)
}

function propsAreEqual(prev, next) {
return JSON.stringify(prev) === JSON.stringify(next)
}
const FenceItemsTable = React.memo(FenceItemsTableNonMemo, propsAreEqual)

export default FenceItemsTable
138 changes: 138 additions & 0 deletions gcs/src/components/missions/fenceItemsTableRow.jsx
Original file line number Diff line number Diff line change
@@ -0,0 +1,138 @@
/*
This component displays the row for a fence item in a table.
*/

import { NumberInput, Select, TableTd, TableTr } from "@mantine/core"
import { useEffect, useState } from "react"
import { coordToInt, intToCoord } from "../../helpers/dataFormatters"
import { MAV_FRAME_LIST } from "../../helpers/mavlinkConstants"
const coordsFractionDigits = 9

export default function FenceItemsTableRow({
index,
fenceItem,
updateFenceItem,
}) {
const [fenceItemData, setFenceItemData] = useState(fenceItem)

useEffect(() => {
setFenceItemData(fenceItem)
}, [fenceItem])

useEffect(() => {
updateFenceItem(fenceItemData)
}, [fenceItemData])

function getFrameName(frameId) {
var frameName = MAV_FRAME_LIST[frameId]

if (frameName.startsWith("MAV_FRAME_")) {
frameName = frameName.replace("MAV_FRAME_", "")
}

return frameName || "UNKNOWN"
}

function updateFenceItemData(key, newVal) {
setFenceItemData({
...fenceItemData,
[key]: newVal,
})
}

return (
<TableTr>
<TableTd>{index}</TableTd>
<TableTd>
<NumberInput
value={fenceItemData.command}
onChange={(value) => updateFenceItemData("command", value)}
min={0}
max={65535}
step={1}
size="xs"
/>
</TableTd>
<TableTd>
<NumberInput
value={fenceItemData.param1}
onChange={(value) => updateFenceItemData("param1", value)}
min={-1000}
max={1000}
step={0.1}
size="xs"
decimalScale={2}
/>
</TableTd>
<TableTd>
<NumberInput
value={fenceItemData.param2}
onChange={(value) => updateFenceItemData("param2", value)}
min={-1000}
max={1000}
step={0.1}
size="xs"
decimalScale={2}
/>
</TableTd>
<TableTd>
<NumberInput
value={fenceItemData.param3}
onChange={(value) => updateFenceItemData("param3", value)}
min={-1000}
max={1000}
step={0.1}
size="xs"
decimalScale={2}
/>
</TableTd>
<TableTd>
<NumberInput
value={fenceItemData.param4}
onChange={(value) => updateFenceItemData("param4", value)}
min={-1000}
max={1000}
step={0.1}
size="xs"
decimalScale={2}
/>
</TableTd>
<TableTd>
<NumberInput
value={intToCoord(fenceItemData.x).toFixed(coordsFractionDigits)}
onChange={(val) => updateFenceItemData("x", coordToInt(val))}
hideControls
/>
</TableTd>
<TableTd>
<NumberInput
value={intToCoord(fenceItemData.y).toFixed(coordsFractionDigits)}
onChange={(val) => updateFenceItemData("y", coordToInt(val))}
hideControls
/>
</TableTd>
<TableTd>
<NumberInput
value={fenceItemData.z}
onChange={(value) => updateFenceItemData("z", value)}
min={-1000}
max={10000}
step={0.1}
size="xs"
decimalScale={2}
/>
</TableTd>
<TableTd>
<Select
value={fenceItemData.frame}
onChange={(value) => updateFenceItemData("frame", value)}
data={Object.entries(MAV_FRAME_LIST).map(([key, value]) => ({
value: key,
label: value.replace("MAV_FRAME_", ""),
}))}
size="xs"
/>
</TableTd>
</TableTr>
)
}
129 changes: 123 additions & 6 deletions gcs/src/missions.jsx
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ import { v4 as uuidv4 } from "uuid"
// Custom component and helpers
import { Button, Divider, Tabs } from "@mantine/core"
import Layout from "./components/layout"
import FenceItemsTable from "./components/missions/fenceItemsTable"
import MissionItemsTable from "./components/missions/missionItemsTable"
import MissionsMapSection from "./components/missions/missionsMap"
import RallyItemsTable from "./components/missions/rallyItemsTable"
Expand Down Expand Up @@ -43,10 +44,41 @@ export default function Missions() {

const [activeTab, setActiveTab] = useState("mission")

// Mission
// Mission - Test data for development
const [missionItems, setMissionItems] = useSessionStorage({
key: "missionItems",
defaultValue: [],
defaultValue: [
{
id: uuidv4(),
seq: 0,
command: 16, // MAV_CMD_NAV_WAYPOINT
frame: 3, // MAV_FRAME_GLOBAL_RELATIVE_ALT
current: 0,
autocontinue: 1,
param1: 0.0,
param2: 0.0,
param3: 0.0,
param4: 0.0,
x: 52.78031970, // Original waypoint 1
y: -0.70979300, // Original waypoint 1
z: 30.0, // altitude
},
{
id: uuidv4(),
seq: 1,
command: 16, // MAV_CMD_NAV_WAYPOINT
frame: 3, // MAV_FRAME_GLOBAL_RELATIVE_ALT
current: 0,
autocontinue: 1,
param1: 0.0,
param2: 0.0,
param3: 0.0,
param4: 0.0,
x: 52.78122830, // Original waypoint 2
y: -0.70989490, // Original waypoint 2
z: 30.0, // altitude
}
],
})
const [fenceItems, setFenceItems] = useSessionStorage({
key: "fenceItems",
Expand All @@ -72,6 +104,7 @@ export default function Missions() {

// System data
const [navControllerOutputData, setNavControllerOutputData] = useState({})
const [isUploading, setIsUploading] = useState(false)

const incomingMessageHandler = useCallback(
() => ({
Expand Down Expand Up @@ -135,10 +168,20 @@ export default function Missions() {
showSuccessNotification(`${data.mission_type} read successfully`)
})

socket.on("upload_mission_result", (data) => {
setIsUploading(false)
if (data.success) {
showSuccessNotification(data.message)
} else {
showErrorNotification(data.message)
}
})

return () => {
socket.off("incoming_msg")
socket.off("home_position_result")
socket.off("current_mission")
socket.off("upload_mission_result")
}
}, [connected])

Expand All @@ -159,6 +202,7 @@ export default function Missions() {
return missionItem
}


function updateMissionItem(updatedMissionItem) {
setMissionItems((prevItems) =>
prevItems.map((item) =>
Expand All @@ -177,13 +221,79 @@ export default function Missions() {
),
)
}
function updateFenceItem(updatedFenceItem) {
setFenceItems((prevItems) =>
prevItems.map((item) =>
item.id === updatedFenceItem.id
? { ...item, ...updatedFenceItem }
: item,
),
)
}

function readMissionFromDrone() {
socket.emit("get_current_mission", { type: activeTab })
}

function writeMissionToDrone() {
return
if (!connected) {
showErrorNotification("Not connected to drone")
return
}

if (isUploading) {
showErrorNotification("Mission upload already in progress")
return
}

let missionData = []
if (activeTab === "mission") {
missionData = missionItems
} else if (activeTab === "fence") {
missionData = fenceItems
} else if (activeTab === "rally") {
missionData = rallyItems
}

if (missionData.length === 0) {
showErrorNotification(`No ${activeTab} items to upload`)
return
}

setIsUploading(true)

// Convert mission items to the format expected by the backend
const formattedMissionData = missionData.map((item, index) => {
const formatted = {
seq: index,
frame: item.frame || 3, // MAV_FRAME_GLOBAL_RELATIVE_ALT
command: item.command || 16, // MAV_CMD_NAV_WAYPOINT
current: item.current || 0,
autocontinue: item.autocontinue || 1,
param1: item.param1 || 0.0,
param2: item.param2 || 0.0,
param3: item.param3 || 0.0,
param4: item.param4 || 0.0,
x: Math.round((item.x || 0) * 1e7), // latitude as integer (1e7 * degrees)
y: Math.round((item.y || 0) * 1e7), // longitude as integer (1e7 * degrees)
z: item.z || 0.0, // altitude
}

return formatted
})

socket.emit("upload_mission", {
type: activeTab,
mission_data: formattedMissionData,
})

// Set a timeout to handle cases where the upload might hang
setTimeout(() => {
if (isUploading) {
setIsUploading(false)
showErrorNotification("Mission upload timed out. Please try again.")
}
}, 30000) // 30 second timeout
}

function importMissionFromFile() {
Expand Down Expand Up @@ -232,13 +342,15 @@ export default function Missions() {
onClick={() => {
writeMissionToDrone()
}}
disabled={!connected}
disabled={!connected || isUploading}
loading={isUploading}
className="grow"
>
Write {activeTab}
{isUploading ? `Uploading ${activeTab}...` : `Write ${activeTab}`}
</Button>
</div>


<Divider className="my-1" />

<div className="flex flex-col gap-4">
Expand Down Expand Up @@ -334,7 +446,12 @@ export default function Missions() {
updateMissionItem={updateMissionItem}
/>
</Tabs.Panel>
<Tabs.Panel value="fence"></Tabs.Panel>
<Tabs.Panel value="fence">
<FenceItemsTable
fenceItems={fenceItems}
updateFenceItem={updateFenceItem}
/>
</Tabs.Panel>
<Tabs.Panel value="rally">
<RallyItemsTable
rallyItems={rallyItems}
Expand Down
Loading