diff --git a/.vscode/settings.json b/.vscode/settings.json
index 8729fded1..0f44916d3 100644
--- a/.vscode/settings.json
+++ b/.vscode/settings.json
@@ -1,24 +1,25 @@
{
- "cSpell.words": [
- "ardupilot",
- "ARSP",
- "centered",
- "chancount",
- "Crosshair",
- "falcongrey",
- "falconred",
- "frametype",
- "frametypename",
- "maplibre",
- "maptilers",
- "mavutil",
- "Motortestpanel",
- "pymavlink",
- "PYQT",
- "RSSI",
- "serialutil",
- "SITL",
- "statustext",
- "SUAS"
- ]
+ "cSpell.words": [
+ "ardupilot",
+ "ARSP",
+ "centered",
+ "chancount",
+ "Crosshair",
+ "falcongrey",
+ "falconred",
+ "frametype",
+ "frametypename",
+ "maplibre",
+ "maptilers",
+ "mavutil",
+ "Motortestpanel",
+ "pymavlink",
+ "PYQT",
+ "RSSI",
+ "serialutil",
+ "SITL",
+ "statustext",
+ "SUAS"
+ ],
+ "mypy-type-checker.args": ["--config-file=/mypy.ini"]
}
diff --git a/gcs/electron/main.ts b/gcs/electron/main.ts
index 67d16110c..a25a29ecf 100644
--- a/gcs/electron/main.ts
+++ b/gcs/electron/main.ts
@@ -566,6 +566,27 @@ app.whenReady().then(() => {
return result
})
+ ipcMain.handle(
+ "app:save-file",
+ async (
+ _event,
+ { filePath, content }: { filePath: string; content: number[] },
+ ) => {
+ try {
+ // Convert number array to Buffer for fs.writeFileSync
+ const buffer = Buffer.from(content)
+ fs.writeFileSync(filePath, buffer as unknown as string)
+ return { success: true }
+ } catch (err) {
+ console.error("Error saving file:", err)
+ return {
+ success: false,
+ error: err instanceof Error ? err.message : "Unknown error",
+ }
+ }
+ },
+ )
+
ipcMain.handle("params:load-params-from-file", async (event) => {
const window = BrowserWindow.fromWebContents(event.sender)
if (!window) {
diff --git a/gcs/electron/preload.js b/gcs/electron/preload.js
index 14a184d51..c7872ccf1 100644
--- a/gcs/electron/preload.js
+++ b/gcs/electron/preload.js
@@ -8,6 +8,7 @@ const ALLOWED_INVOKE_CHANNELS = [
"fla:clear-recent-logs",
"fla:get-messages",
"app:get-save-file-path",
+ "app:save-file",
"app:get-node-env",
"app:get-version",
"app:is-mac",
diff --git a/gcs/src/components/config/ftp.jsx b/gcs/src/components/config/ftp.jsx
index 010917d24..857dde802 100644
--- a/gcs/src/components/config/ftp.jsx
+++ b/gcs/src/components/config/ftp.jsx
@@ -12,17 +12,26 @@ import { Button, Group, LoadingOverlay, Tree } from "@mantine/core"
import { IconFile, IconFolder, IconFolderOpen } from "@tabler/icons-react"
import { useEffect, useMemo } from "react"
import { useDispatch, useSelector } from "react-redux"
+import {
+ showErrorNotification,
+ showSuccessNotification,
+} from "../../helpers/notification"
import {
emitListFiles,
+ emitReadFile,
resetFiles,
selectFiles,
+ selectIsReadingFile,
selectLoadingListFiles,
+ selectReadFileData,
} from "../../redux/slices/ftpSlice"
export default function Ftp() {
const dispatch = useDispatch()
const files = useSelector(selectFiles)
const loadingListFiles = useSelector(selectLoadingListFiles)
+ const isReadingFile = useSelector(selectIsReadingFile)
+ const readFileData = useSelector(selectReadFileData)
const convertedFiles = useMemo(() => {
if (!files || files.length === 0) return []
@@ -52,6 +61,24 @@ export default function Ftp() {
})
}, [files])
+ const fileContentString = useMemo(() => {
+ if (readFileData) {
+ try {
+ const decoder = new TextDecoder("utf-8")
+ return {
+ success: true,
+ content: decoder.decode(new Uint8Array(readFileData.file_data)),
+ }
+ } catch (e) {
+ return {
+ success: false,
+ content: `Error decoding file content: ${e.message}`,
+ }
+ }
+ }
+ return null
+ }, [readFileData])
+
useEffect(() => {
if (files.length === 0) {
dispatch(emitListFiles({ path: "/" }))
@@ -63,53 +90,114 @@ export default function Ftp() {
if (node.children === undefined) {
dispatch(emitListFiles({ path: node.path }))
}
+ } else {
+ dispatch(emitReadFile({ path: node.path }))
+ }
+ }
+
+ async function downloadReadFile() {
+ if (fileContentString && fileContentString.success) {
+ const options = {
+ title: "Save file",
+ defaultPath: readFileData.file_name,
+ filters: [{ name: "All Files", extensions: ["*"] }],
+ }
+
+ const result = await window.ipcRenderer.invoke(
+ "app:get-save-file-path",
+ options,
+ )
+
+ if (!result.canceled && result.filePath) {
+ const saveResult = await window.ipcRenderer.invoke("app:save-file", {
+ filePath: result.filePath,
+ content: readFileData.file_data,
+ })
+
+ if (saveResult.success) {
+ showSuccessNotification(
+ `File saved successfully to: ${result.filePath}`,
+ )
+ } else {
+ showErrorNotification("Error saving file:", saveResult.error)
+ }
+ }
}
}
return (
-
-
-
- {loadingListFiles &&
Loading files...
}
-
-
-
(
-
- {node.is_dir ? (
- <>
- {expanded ? (
-
- ) : (
-
- )}
- >
- ) : (
-
- )}
-
- {
- handleFileClick(node)
+
+
+
+ {loadingListFiles &&
Loading files...
}
+
+
(
+
+ {node.is_dir ? (
+ <>
+ {expanded ? (
+
+ ) : (
+
+ )}
+ >
+ ) : (
+
+ )}
+ {
+ handleFileClick(node)
+ }}
+ >
+ {node.label}
+
+
+ )}
+ />
+
+
+ {fileContentString !== null && (
+
+
+
+
+
+ {fileContentString.success ? (
+
+ {fileContentString.content}
+
+ ) : (
+
{fileContentString.content}
+ )}
+
+
)}
- />
+
)
}
diff --git a/gcs/src/redux/middleware/emitters.js b/gcs/src/redux/middleware/emitters.js
index d94461afc..6b1712c76 100644
--- a/gcs/src/redux/middleware/emitters.js
+++ b/gcs/src/redux/middleware/emitters.js
@@ -35,7 +35,12 @@ import {
setCurrentPage,
setIsForwarding,
} from "../slices/droneConnectionSlice"
-import { emitListFiles, setLoadingListFiles } from "../slices/ftpSlice"
+import {
+ emitListFiles,
+ emitReadFile,
+ setIsReadingFile,
+ setLoadingListFiles,
+} from "../slices/ftpSlice"
import {
emitControlMission,
emitExportMissionToFile,
@@ -383,6 +388,15 @@ export function handleEmitters(socket, store, action) {
store.dispatch(setLoadingListFiles(true))
},
},
+ {
+ emitter: emitReadFile,
+ callback: () => {
+ socket.socket.emit("read_file", {
+ path: action.payload.path,
+ })
+ store.dispatch(setIsReadingFile(true))
+ },
+ },
]
for (const { emitter, callback } of emitHandlers) {
diff --git a/gcs/src/redux/middleware/socketMiddleware.js b/gcs/src/redux/middleware/socketMiddleware.js
index 7ab2aa7bc..7b9d49d7d 100644
--- a/gcs/src/redux/middleware/socketMiddleware.js
+++ b/gcs/src/redux/middleware/socketMiddleware.js
@@ -78,7 +78,9 @@ import {
import {
addFiles,
resetFiles,
+ setIsReadingFile,
setLoadingListFiles,
+ setReadFileData,
} from "../slices/ftpSlice.js"
import {
addIdToItem,
@@ -178,6 +180,7 @@ const ConfigSpecificSocketEvents = Object.freeze({
const FtpSpecificSocketEvents = Object.freeze({
onListFilesResult: "list_files_result",
+ onReadFileResult: "read_file_result",
})
const socketMiddleware = (store) => {
@@ -409,6 +412,8 @@ const socketMiddleware = (store) => {
store.dispatch(resetMessages())
store.dispatch(resetGpsTrack())
store.dispatch(resetFiles())
+ store.dispatch(setIsReadingFile(false))
+ store.dispatch(setReadFileData(null))
})
// Link stats
@@ -1091,6 +1096,16 @@ const socketMiddleware = (store) => {
showErrorNotification(msg.message)
}
})
+
+ socket.socket.on(FtpSpecificSocketEvents.onReadFileResult, (msg) => {
+ store.dispatch(setIsReadingFile(false))
+ if (msg.success) {
+ showSuccessNotification(msg.message)
+ store.dispatch(setReadFileData(msg.data))
+ } else {
+ showErrorNotification(msg.message)
+ }
+ })
} else {
// Turn off socket events
Object.values(DroneSpecificSocketEvents).map((event) =>
diff --git a/gcs/src/redux/slices/ftpSlice.js b/gcs/src/redux/slices/ftpSlice.js
index 5455d2430..81d6b2de9 100644
--- a/gcs/src/redux/slices/ftpSlice.js
+++ b/gcs/src/redux/slices/ftpSlice.js
@@ -5,6 +5,8 @@ const ftpSlice = createSlice({
initialState: {
files: [],
loadingListFiles: false,
+ isReadingFile: false,
+ readFileData: null,
},
reducers: {
resetFiles: (state) => {
@@ -65,18 +67,40 @@ const ftpSlice = createSlice({
setLoadingListFiles: (state, action) => {
state.loadingListFiles = action.payload
},
+ setIsReadingFile: (state, action) => {
+ state.isReadingFile = action.payload
+ },
+ setReadFileData: (state, action) => {
+ state.readFileData = action.payload
+ },
emitListFiles: () => {},
+ emitReadFile: () => {},
},
selectors: {
selectFiles: (state) => state.files,
selectLoadingListFiles: (state) => state.loadingListFiles,
+ selectIsReadingFile: (state) => state.isReadingFile,
+ selectReadFileData: (state) => state.readFileData,
},
})
-export const { resetFiles, addFiles, setLoadingListFiles, emitListFiles } =
- ftpSlice.actions
+export const {
+ resetFiles,
+ addFiles,
+ setLoadingListFiles,
+ setIsReadingFile,
+ setReadFileData,
+
+ emitListFiles,
+ emitReadFile,
+} = ftpSlice.actions
-export const { selectFiles, selectLoadingListFiles } = ftpSlice.selectors
+export const {
+ selectFiles,
+ selectLoadingListFiles,
+ selectIsReadingFile,
+ selectReadFileData,
+} = ftpSlice.selectors
export default ftpSlice
diff --git a/radio/app/controllers/ftpController.py b/radio/app/controllers/ftpController.py
index 533c9e2af..ed0185a7a 100644
--- a/radio/app/controllers/ftpController.py
+++ b/radio/app/controllers/ftpController.py
@@ -2,8 +2,9 @@
import struct
import time
+from io import BytesIO
from threading import current_thread
-from typing import TYPE_CHECKING, List, Optional
+from typing import TYPE_CHECKING, List, Optional, Tuple
from app.customTypes import Number, Response
from pymavlink import mavftp, mavftp_op
@@ -25,10 +26,23 @@ def __init__(self, drone: Drone) -> None:
self.seq: int = 0
self.session: int = 0
self.last_op: Optional[mavftp_op.FTP_OP] = None
+
+ # Directory listing state
self.dir_offset: int = 0
self.list_result: List[mavftp.DirectoryEntry] = []
self.list_temp_result: List[mavftp.DirectoryEntry] = []
+ # Read/download state
+ self.read_buffer: BytesIO = BytesIO()
+ self.read_total: int = 0
+ self.read_gaps: List[Tuple[int, int]] = [] # List of (offset, size) tuples
+ self.reached_eof: bool = False
+ self.requested_size: int = 0
+ self.requested_offset: int = 0
+ self.remote_file_size: Optional[int] = None
+ self.burst_size: int = 80 # Default burst size
+ self.last_burst_read: Optional[float] = None
+
self._sendFtpCommand(
mavftp_op.FTP_OP(
self.seq,
@@ -132,10 +146,10 @@ def _processFtpResponse(self, op_name: str, timeout: Number = 5) -> Response:
"message": "Session terminated successfully",
}
- # Handle list directory responses
if response_op.req_opcode == mavftp_op.OP_ResetSessions:
return self._handleResetSessionsResponse(response_op)
elif response_op.req_opcode == mavftp_op.OP_ListDirectory:
+ # Handle list directory response
handling_finished = self._handleListFilesResponse(response_op)
if handling_finished:
@@ -143,6 +157,31 @@ def _processFtpResponse(self, op_name: str, timeout: Number = 5) -> Response:
"success": True,
"message": "Directory listing retrieved successfully",
}
+ elif response_op.req_opcode == mavftp_op.OP_OpenFileRO:
+ # Handle file open response
+ success = self._handleOpenFileReadOnlyResponse(response_op)
+ if not success:
+ return {
+ "success": False,
+ "message": "Failed to open file for reading",
+ }
+ # Continue listening for burst read responses
+ elif response_op.req_opcode == mavftp_op.OP_BurstReadFile:
+ # Handle burst read response
+ is_complete = self._handleBurstReadResponse(response_op)
+ if is_complete:
+ return {
+ "success": True,
+ "message": "File read completed successfully",
+ }
+ elif response_op.req_opcode == mavftp_op.OP_ReadFile:
+ # Handle gap fill response
+ is_complete = self._handleReadFileResponse(response_op)
+ if is_complete:
+ return {
+ "success": True,
+ "message": "File read completed successfully",
+ }
else:
self.drone.logger.info(
f"Received unknown FTP response: {response_op.opcode} with {response_op.size} bytes for operation {op_name}"
@@ -414,3 +453,323 @@ def listFiles(self, path: str) -> Response:
"message": "Directory listing retrieved successfully",
"data": self._convertDirectoryEntriesToDicts(self.list_result, path),
}
+
+ def readFile(
+ self, path: str, size: Optional[int] = None, offset: int = 0
+ ) -> Response:
+ """
+ Read/download a file from the drone using MAVFTP.
+
+ Args:
+ path (str): The file path to read.
+ size (Optional[int]): Number of bytes to read. If None, reads entire file.
+ offset (int): Offset in bytes to start reading from.
+
+ Returns:
+ Response: A response object containing the file data or error message.
+ """
+ if not path:
+ return {
+ "success": False,
+ "message": "File path cannot be empty",
+ }
+
+ # Reset read state
+ self.read_buffer = BytesIO()
+ self.read_total = 0
+ self.read_gaps = []
+ self.reached_eof = False
+ self.requested_offset = offset
+ self.requested_size = (
+ size if size is not None else 0
+ ) # 0 means read entire file
+ self.remote_file_size = None
+ self.last_burst_read = None
+
+ # Send OpenFileRO command
+ encoded_path = bytearray(path, "ascii")
+ op = mavftp_op.FTP_OP(
+ self.seq,
+ self.session,
+ mavftp_op.OP_OpenFileRO,
+ len(encoded_path),
+ 0,
+ 0,
+ 0,
+ encoded_path,
+ )
+
+ self.drone.logger.info(
+ f"Reading file: {path} (offset={offset}, size={size if size else 'entire file'})"
+ )
+
+ self._sendFtpCommand(op)
+ response = self._processFtpResponse("read_file", timeout=30)
+
+ if response.get("success", False) is False:
+ return response
+
+ # Extract the requested portion of the data
+ self.read_buffer.seek(0)
+ all_data = self.read_buffer.read()
+
+ if self.requested_size > 0:
+ # Return only the requested size from the requested offset
+ result_data = all_data[
+ self.requested_offset : self.requested_offset + self.requested_size
+ ]
+ else:
+ # Return entire file
+ result_data = all_data
+
+ self.drone.logger.info(
+ f"Successfully read {len(result_data)} bytes from file: {path}"
+ )
+
+ return {
+ "success": True,
+ "message": "File read successfully",
+ "data": {"file_data": result_data, "file_name": path.split("/")[-1]},
+ }
+
+ def _handleOpenFileReadOnlyResponse(self, response_op: mavftp_op.FTP_OP) -> bool:
+ """
+ Handle the response for an OpenFileRO operation.
+
+ Args:
+ response_op (mavftp_op.FTP_OP): The FTP operation response to handle.
+
+ Returns:
+ bool: True if the operation was successful and should continue reading.
+ """
+ if response_op.opcode == mavftp_op.OP_Ack:
+ # Extract file size from payload if present
+ if (
+ response_op.size == 4
+ and response_op.payload
+ and len(response_op.payload) >= 4
+ ):
+ self.remote_file_size = (
+ response_op.payload[0]
+ | (response_op.payload[1] << 8)
+ | (response_op.payload[2] << 16)
+ | (response_op.payload[3] << 24)
+ )
+
+ self.drone.logger.info(
+ f"Remote file size: {self.remote_file_size} bytes"
+ )
+
+ # If no specific size was requested, read the entire file
+ if self.requested_size == 0 and self.remote_file_size is not None:
+ self.requested_size = self.remote_file_size
+
+ # Position the buffer at the requested offset
+ self.read_buffer.seek(self.requested_offset)
+
+ # Send first burst read request
+ burst_read_op = mavftp_op.FTP_OP(
+ self.seq,
+ self.session,
+ mavftp_op.OP_BurstReadFile,
+ self.burst_size,
+ 0,
+ 0,
+ self.requested_offset,
+ None,
+ )
+ self.last_burst_read = time.time()
+ self._sendFtpCommand(burst_read_op)
+ return True
+ else:
+ # NACK or error
+ if (
+ response_op.opcode == mavftp_op.OP_Nack
+ and response_op.payload is not None
+ and len(response_op.payload) == 1
+ and response_op.payload[0] == mavftp.FtpError.FileNotFound.value
+ ):
+ self.drone.logger.error(f"File not found: opcode={response_op.opcode}")
+ return False
+
+ self.drone.logger.error(
+ f"Failed to open file for reading: opcode={response_op.opcode}"
+ )
+ return False
+
+ def _handleBurstReadResponse(self, response_op: mavftp_op.FTP_OP) -> bool:
+ """
+ Handle the response for a BurstReadFile operation.
+
+ Args:
+ response_op (mavftp_op.FTP_OP): The FTP operation response to handle.
+
+ Returns:
+ bool: True if reading is complete, False if more data is expected.
+ """
+ if response_op.opcode == mavftp_op.OP_Ack and response_op.payload:
+ self.last_burst_read = time.time()
+ current_pos = self.read_buffer.tell()
+
+ if response_op.offset < current_pos:
+ # Writing an earlier portion - check if it fills a gap
+ gap = (response_op.offset, len(response_op.payload))
+ if gap in self.read_gaps:
+ self.read_gaps.remove(gap)
+ self.drone.logger.debug(
+ f"Filled gap at offset {gap[0]}, size {gap[1]}"
+ )
+ else:
+ self.drone.logger.debug(
+ f"Duplicate data at offset {response_op.offset}"
+ )
+ return False
+
+ # Write the payload and return to current position
+ self.read_buffer.seek(response_op.offset)
+ self.read_buffer.write(response_op.payload)
+ self.read_total += len(response_op.payload)
+ self.read_buffer.seek(current_pos)
+
+ elif response_op.offset > current_pos:
+ # We have a gap
+ gap_size = response_op.offset - current_pos
+
+ # Split large gaps into smaller chunks
+ max_chunk = self.burst_size
+ remaining_offset = current_pos
+ remaining_size = gap_size
+
+ while remaining_size > 0:
+ chunk_size = min(remaining_size, max_chunk)
+ self.read_gaps.append((remaining_offset, chunk_size))
+ remaining_offset += chunk_size
+ remaining_size -= chunk_size
+
+ self.drone.logger.debug(
+ f"Gap detected: {gap_size} bytes at offset {current_pos}"
+ )
+
+ # Write the payload
+ self.read_buffer.seek(response_op.offset)
+ self.read_buffer.write(response_op.payload)
+ self.read_total += len(response_op.payload)
+
+ else:
+ # Sequential write
+ self.read_buffer.write(response_op.payload)
+ self.read_total += len(response_op.payload)
+
+ # Check if burst is complete
+ if response_op.burst_complete:
+ if 0 < response_op.size < self.burst_size:
+ # EOF reached
+ self.reached_eof = True
+ self.drone.logger.debug(
+ f"EOF reached at {self.read_buffer.tell()} bytes with {len(self.read_gaps)} gaps"
+ )
+
+ if len(self.read_gaps) == 0:
+ # All data received
+ return True
+
+ # Request missing gaps
+ self._requestGaps()
+ return False
+ else:
+ # Continue reading
+ next_offset = response_op.offset + response_op.size
+ burst_read_op = mavftp_op.FTP_OP(
+ self.seq,
+ self.session,
+ mavftp_op.OP_BurstReadFile,
+ self.burst_size,
+ 0,
+ 0,
+ next_offset,
+ None,
+ )
+ self._sendFtpCommand(burst_read_op)
+ return False
+
+ elif response_op.opcode == mavftp_op.OP_Nack:
+ # Check error code
+ if response_op.payload and len(response_op.payload) > 0:
+ error_code = response_op.payload[0]
+ if error_code == mavftp.FtpError.EndOfFile.value:
+ self.reached_eof = True
+ self.drone.logger.debug(
+ f"EOF (NACK) at {self.read_buffer.tell()} bytes with {len(self.read_gaps)} gaps"
+ )
+
+ if len(self.read_gaps) == 0:
+ return True
+
+ # Request missing gaps
+ self._requestGaps()
+ return False
+ else:
+ self.drone.logger.error(f"Read error: error code {error_code}")
+ return True # Stop reading
+
+ return False
+
+ def _handleReadFileResponse(self, response_op: mavftp_op.FTP_OP) -> bool:
+ """
+ Handle the response for a ReadFile (gap fill) operation.
+
+ Args:
+ response_op (mavftp_op.FTP_OP): The FTP operation response to handle.
+
+ Returns:
+ bool: True if reading is complete, False otherwise.
+ """
+ if response_op.opcode == mavftp_op.OP_Ack and response_op.payload:
+ gap = (response_op.offset, response_op.size)
+
+ if gap in self.read_gaps:
+ self.read_gaps.remove(gap)
+ current_pos = self.read_buffer.tell()
+
+ # Write gap data
+ self.read_buffer.seek(response_op.offset)
+ self.read_buffer.write(response_op.payload)
+ self.read_total += len(response_op.payload)
+ self.read_buffer.seek(current_pos)
+
+ self.drone.logger.debug(
+ f"Filled gap at offset {response_op.offset}, size {response_op.size}"
+ )
+
+ # Check if all gaps are filled
+ if len(self.read_gaps) == 0 and (
+ self.reached_eof or self.read_total >= self.requested_size
+ ):
+ return True
+
+ elif response_op.opcode == mavftp_op.OP_Nack:
+ self.drone.logger.error(
+ f"Failed to read gap at offset {response_op.offset}"
+ )
+
+ return False
+
+ def _requestGaps(self) -> None:
+ """Request missing data chunks (gaps) using OP_ReadFile."""
+ for gap_offset, gap_size in self.read_gaps[
+ :5
+ ]: # Request up to 5 gaps at a time
+ read_op = mavftp_op.FTP_OP(
+ self.seq,
+ self.session,
+ mavftp_op.OP_ReadFile,
+ gap_size,
+ 0,
+ 0,
+ gap_offset,
+ None,
+ )
+ self._sendFtpCommand(read_op)
+ self.drone.logger.debug(
+ f"Requesting gap: offset={gap_offset}, size={gap_size}"
+ )
diff --git a/radio/app/endpoints/ftp.py b/radio/app/endpoints/ftp.py
index 7e87b8ccb..6fb8a622b 100644
--- a/radio/app/endpoints/ftp.py
+++ b/radio/app/endpoints/ftp.py
@@ -9,6 +9,10 @@ class ListFilesType(TypedDict):
path: str
+class ReadFileType(TypedDict):
+ path: str
+
+
@socketio.on("list_files")
def listFiles(data: ListFilesType) -> None:
"""
@@ -17,7 +21,7 @@ def listFiles(data: ListFilesType) -> None:
Args:
data: The data from the client, this contains "path" which is the directory path to list files from
"""
- if droneStatus.state != "config":
+ if droneStatus.state is None or "config" not in droneStatus.state:
socketio.emit(
"params_error",
{"message": "You must be on the config screen to access FTP operations"},
@@ -33,3 +37,40 @@ def listFiles(data: ListFilesType) -> None:
result = droneStatus.drone.ftpController.listFiles(path)
socketio.emit("list_files_result", result)
+
+
+@socketio.on("read_file")
+def readFile(data: ReadFileType) -> None:
+ """
+ Read/download a file from the drone's FTP server
+
+ Args:
+ data: The data from the client, this contains "path" which is the file path to read/download
+ """
+ if droneStatus.state is None or "config" not in droneStatus.state:
+ socketio.emit(
+ "params_error",
+ {"message": "You must be on the config screen to access FTP operations"},
+ )
+ logger.debug(f"Current state: {droneStatus.state}")
+ return
+
+ if not droneStatus.drone:
+ return notConnectedError(action="read file")
+
+ path = data.get("path", None)
+ if path is None:
+ socketio.emit(
+ "read_file_result", {"success": False, "message": "Missing file path"}
+ )
+ return
+
+ result = droneStatus.drone.ftpController.readFile(path)
+
+ # Convert bytes to list for SocketIO serialization
+ if result.get("success") and "data" in result:
+ data_dict = result["data"]
+ if isinstance(data_dict, dict) and "file_data" in data_dict:
+ data_dict["file_data"] = list(data_dict["file_data"])
+
+ socketio.emit("read_file_result", result)
diff --git a/radio/app/utils.py b/radio/app/utils.py
index 1693e5fe3..f5562cefc 100644
--- a/radio/app/utils.py
+++ b/radio/app/utils.py
@@ -1,6 +1,6 @@
import logging
import sys
-from typing import Any, List, Optional
+from typing import Any, List, Optional, Union
from pymavlink import mavutil
from serial.tools import list_ports
@@ -163,7 +163,7 @@ def droneConnectStatusCb(msg: ConnectionDataType) -> None:
socketio.emit("drone_connect_status", msg)
-def notConnectedError(action: str | None = None) -> None:
+def notConnectedError(action: Optional[str] = None) -> None:
"""
Send error to the socket indicating that drone connection must be established to complete this action
@@ -178,7 +178,7 @@ def notConnectedError(action: str | None = None) -> None:
)
-def missingParameterError(endpoint: str, params: str | list[str]) -> None:
+def missingParameterError(endpoint: str, params: Union[str, list[str]]) -> None:
""" "
Send error to the socket indicating that a request made to the server was missing required parameters
diff --git a/radio/tests/ftp_test_files/expected_locations.txt b/radio/tests/ftp_test_files/expected_locations.txt
new file mode 100644
index 000000000..3930c5745
--- /dev/null
+++ b/radio/tests/ftp_test_files/expected_locations.txt
@@ -0,0 +1,106 @@
+#NAME=latitude,longitude,absolute-altitude,heading
+OSRF0=37.4003371,-122.0800351,0,353
+OSRF0_PILOTSBOX=37.4003371,-122.0800351,2,270
+CMAC=-35.363261,149.165230,584,353
+CMAC2=-35.362889,149.165221,584,270
+CMAC_South=-35.363261,149.165230,584,173
+CMAC_PILOTSBOX=-35.362734,149.165300,586,270
+CMAC_PILOTSBOX2=-35.362749,149.165359,584,270
+Kingaroy=-26.583528,151.840440,444,169
+AVC=40.0713749,-105.2297889,1583.702759,246
+AVC_copter=40.072842,-105.230575,1586,0
+AVC_plane=40.072842,-105.230575,1586,80
+McMillan=35.718719,-120.769818,275,295
+McMillan_East=35.7168007,-120.7644466,275,295
+TomCarpark=26.048950,-80.254219,6,270
+Ballarat=-37.598705,143.881744,485,165
+CRAMS=-27.675284,152.519307,58,285 # Calvert Radio Aero Modeller's Society
+3DRBerkeley=37.872991,-122.302348,20,260
+BMAC=-35.226343,149.132122,588,301
+LGAT=37.889063,23.731863,21,330
+BHV=53.547767,8.626440,0,324
+QMAC=-35.363724,149.430011,740,312
+Karuizawa=36.323203,138.618215,926,0
+Dalby=-27.274439,151.290064,343,8.7
+RFRanch=37.118079,-2.773690,1297.88,180
+KSFO=37.619373,-122.376637,5.3,118
+NFSC=53.637561,9.929800,13,345
+Rotherham=53.275131,-1.19404,21,360
+LeeField=32.42553,-84.79109,75,260
+Sterling=38.982480,-77.439567,88,90
+EPIgijon=43.521902,-5.624310,22,0
+PerkinsField=36.163609,-78.806864,137,20
+KNUI=38.145322,-76.426652,7,70
+Range11=41.360461,-74.032838,220,180
+Flicker=39.018801,-104.893081,2158,180
+ElliottField=34.458281,-84.180209,450,130
+CobbCountyRC=34.013819,-84.724446,280,105
+GrupoSicoss=19.316518,-99.220255,0,0
+Garrawarra=-34.159752,150.967395,293,165
+Snarbyeidet=69.775839,19.548929,87,170
+Breivikeidet=69.624025,19.414047,55,235
+Hata=35.671497,140.083934,6,165
+TagusPark=38.740195,-9.301843,151,0
+Marcopter=44.806968,11.610389,0,90
+HMAS=-33.661500,150.841431,18,0
+RATBeach=33.810313,-118.393867,0,270
+Carstensz=-35.331302,149.132103,606,60
+Skyrocket=33.982069,-118.426372,11,134
+SkyViperFactory=23.021754,114.073139,13,0
+KazakoshiPark=36.321909,138.596021,932,0
+SKT=44.850687,-0.684029,45,0
+UChicago=41.7886079,-87.59871329999999,191,0
+Yachiyo=35.770481,140.107929,36,90
+Tyndall=30.0142232,-85.4984701,7,0
+Elvenes=68.871422,17.986690,17,256
+Kawachi=35.879129,140.339683,7,0
+SpringValley=-35.280252,149.005821,580.8,5
+SpringValley2=-35.28240059,149.00542037,582,10
+SpringValley3=-35.28240515,149.00716878,579,12.6
+SpringValley4=-35.2824768,149.0071759,594.99,0
+SpringValleyRoad=-35.28899126,149.00553365,603,162.7
+Pyramid=29.9764,31.1339,0,0
+AAMEastField=39.842288,-105.212928,1809,106
+HachinoheMine=40.4539496,141.5419051,56,270
+HighwayField=-33.950458,22.977709,240,300
+AAMWestField=39.842218,-105.219375,1814,90.5
+EliField=40.059488,-88.551314,206,37
+Goretovka=55.9689,37.1101,200,290
+Kris=22.74005960,120.30975281,21,0
+ARACE_copter=47.5211929,18.8082355,198,55
+ARACE_plane=47.5210876,18.8083948,198,55
+ARACE_hand=47.5211516,18.8081607,198,55
+NDRCC=33.24065965,-96.93759168,163.5,167
+Boquig=16.090473,120.361478,3,0
+Semisopochnoi=51.9634,179.756,120.0,90.0
+Unalga=51.578,-179.0483,42.0,270.0
+Rabi=-16.51273251,179.97642023,7.5,90
+KFC=34.8412920,136.2154873,196.36,338
+KawaguchiLake=35.4712023,138.7450261,965,90
+GrandCanyon=36.146,-113.89,1425.6,90
+YPG=32.976658,-114.266699,252.97,235
+Yuma=32.638083,-114.403104,95,0
+Williams=39.16124,-122.13187,23,0
+WilliamsVtol=39.1652640,-122.131755,23,180
+SCCMAS=37.1730398,-121.6815865,102,315
+ARPstrip_NZ=-43.6544343,172.5031829,0,156 #Strip in New Zealand
+ARPstrip_NZ_S=-43.6541316,172.5029844,0,156 #Strip in New Zealand, South takeoff
+ARPstrip_NZ_N=-43.6545022,172.5031883,0,336 #Strip in New Zealand, North takeoff
+CMAC_NZ_E=-43.47493266,172.318144,0,84 #Christchurch MAC, New Zealand, East takeoff
+CMAC_NZ_W=-43.47493266,172.318144,0,264 #Christchurch MAC, New Zealand, West takeoff
+OSPN=30.53202,-97.62892,199,7 #Old Settlers Park , Austin, TX, North takeof
+OSP=30.53202,-97.62892,199,187 #Old Settlers Park , Austin, TX, South takeof
+KalaupapaCliffs=21.16564233,-156.88680160,165.25,0
+Portmoak=56.191,-3.323271,164,270
+LakeGeorgeLookout=-35.10122092,149.37517574,708.12,90
+RF_AirStadium=36.893328,-2.720371,1434,0
+RF_BuenaVista=37.093686,-2.890969,2390,0
+RF_Castle=37.090662,-3.074557,2736,0
+RF_Garage=37.621798,-2.646596,788,0
+Madera=36.9287648,-119.8498046,82,290
+Peg=36.7099085,-119.4076592,141,289
+SFO_Bay=37.62561973,-122.33235387,0.0,0
+Egge=60.215720,10.324071,198,303
+Gundaroo=-35.02349196,149.26496411,576.8,0
+Kaga=36.3268982,136.3316638,44,0
+UCSB=34.413963,-119.848946,0,0
diff --git a/radio/tests/test_ftp.py b/radio/tests/test_ftp.py
index be849261f..e90092c63 100644
--- a/radio/tests/test_ftp.py
+++ b/radio/tests/test_ftp.py
@@ -1,8 +1,15 @@
+import os
+
from flask_socketio.test_client import SocketIOTestClient
from . import falcon_test
from .helpers import NoDrone
+FTP_FILES_PATH = os.path.join(
+ os.path.dirname(__file__),
+ "ftp_test_files",
+)
+
@falcon_test(pass_drone_status=True)
def test_listFiles_wrongState_failure(socketio_client: SocketIOTestClient, droneStatus):
@@ -133,3 +140,104 @@ def test_listFiles_noDroneConnection_failure(
assert socketio_result["args"][0] == {
"message": "Must be connected to the drone to list files."
}
+
+
+@falcon_test(pass_drone_status=True)
+def test_readFile_wrongState_failure(socketio_client: SocketIOTestClient, droneStatus):
+ droneStatus.state = "dashboard"
+ socketio_client.emit("read_file", {"path": "/@ROMFS/locations.txt"})
+ socketio_result = socketio_client.get_received()[0]
+
+ assert socketio_result["name"] == "params_error"
+ assert socketio_result["args"][0] == {
+ "message": "You must be on the config screen to access FTP operations"
+ }
+
+
+@falcon_test(pass_drone_status=True)
+def test_readFile_missingPath_failure(socketio_client: SocketIOTestClient, droneStatus):
+ droneStatus.state = "config"
+ socketio_client.emit("read_file", {})
+ socketio_result = socketio_client.get_received()[0]
+
+ assert socketio_result["name"] == "read_file_result"
+ assert socketio_result["args"][0] == {
+ "success": False,
+ "message": "Missing file path",
+ }
+
+
+@falcon_test(pass_drone_status=True)
+def test_readFile_emptyPath_failure(socketio_client: SocketIOTestClient, droneStatus):
+ droneStatus.state = "config"
+ socketio_client.emit("read_file", {"path": ""})
+ socketio_result = socketio_client.get_received()[0]
+
+ assert socketio_result["name"] == "read_file_result"
+ assert socketio_result["args"][0] == {
+ "success": False,
+ "message": "File path cannot be empty",
+ }
+
+
+@falcon_test(pass_drone_status=True)
+def test_readFile_validFile_success(socketio_client: SocketIOTestClient, droneStatus):
+ droneStatus.state = "config"
+ socketio_client.emit("read_file", {"path": "/@ROMFS/locations.txt"})
+ socketio_result = socketio_client.get_received()[0]
+
+ expected_file_path = os.path.join(FTP_FILES_PATH, "expected_locations.txt")
+ with open(expected_file_path, "rb") as f:
+ expected_content = f.read()
+
+ assert socketio_result["name"] == "read_file_result"
+ assert socketio_result["args"][0]["success"] is True
+ assert socketio_result["args"][0]["message"] == "File read successfully"
+ assert socketio_result["args"][0]["data"]["file_data"] == list(expected_content)
+ assert socketio_result["args"][0]["data"]["file_name"] == "locations.txt"
+
+
+@falcon_test(pass_drone_status=True)
+def test_readFile_nonExistentFile_failure(
+ socketio_client: SocketIOTestClient, droneStatus
+):
+ droneStatus.state = "config"
+ socketio_client.emit("read_file", {"path": "/random/file/that/does/not/exist.txt"})
+ socketio_result = socketio_client.get_received()[0]
+
+ assert socketio_result["name"] == "read_file_result"
+ assert socketio_result["args"][0] == {
+ "success": False,
+ "message": "Failed to open file for reading",
+ }
+
+
+@falcon_test(pass_drone_status=True)
+def test_readFile_directoryPath_failure(
+ socketio_client: SocketIOTestClient, droneStatus
+):
+ droneStatus.state = "config"
+ socketio_client.emit("read_file", {"path": "/@ROMFS"})
+ socketio_result = socketio_client.get_received()[0]
+
+ assert socketio_result["name"] == "read_file_result"
+ assert socketio_result["args"][0] == {
+ "success": False,
+ "message": "Failed to open file for reading",
+ }
+
+
+@falcon_test(pass_drone_status=True)
+def test_readFile_noDroneConnection_failure(
+ socketio_client: SocketIOTestClient, droneStatus
+):
+ droneStatus.state = "config"
+
+ with NoDrone():
+ socketio_client.emit("read_file", {"path": "/@ROMFS/locations.txt"})
+ socketio_result = socketio_client.get_received()[0]
+
+ assert socketio_result["name"] == "connection_error"
+ assert socketio_result["args"][0] == {
+ "message": "Must be connected to the drone to read file."
+ }