From 333d09bc8647d49306e33c37a67b5d9507c0c11c Mon Sep 17 00:00:00 2001 From: j444zhan Date: Sun, 1 Dec 2024 12:00:34 -0500 Subject: [PATCH 1/5] groundside script to open and read data from files in pixhawk file system --- modules/groundside_scripts.py | 160 ++++++++++++++++++++++++++++++++++ 1 file changed, 160 insertions(+) create mode 100644 modules/groundside_scripts.py diff --git a/modules/groundside_scripts.py b/modules/groundside_scripts.py new file mode 100644 index 00000000..23ab749b --- /dev/null +++ b/modules/groundside_scripts.py @@ -0,0 +1,160 @@ +""" +Groundside scripts to receive GPS location messages +""" + +import struct +import sys +from pymavlink import mavutil + +# connection params +CONNECTION_ADDRESS = "tcp:127.0.0.1:14550" +TIMEOUT = 5.0 +DELAY_TIME = 1.0 + +# file path to read from +# 1. start up connection on mission planner +# 2. mavlink and establish write tcp connection +# 3. config menu -> MAVFtp -> simulation drone file paths +FILE_PATH = b"/@ROMFS/locations.txt" +SEQ_NUM = 0 + + +def send_ftp_command( + connection: mavutil.mavlink_connection, + seq_num: int, + opcode: int, + req_opcode: int, + session: int, + offset: int, + size: int, + payload: bytes, +) -> None: + """ + Send an FTP command to the vehicle. + + Args: + connection (mavutil.mavlink_connection): MAVLink connection object. + opcode (int): FTP command opcode. + req_opcode (int): Requested opcode. + session (int): Session ID. + offset (int): Offset in the file. + size (int): Size of the payload. + payload (bytes): Payload data. + """ + ftp_payload = bytearray(251) # ftp payload size + + # packing payload in file system + ftp_payload[0:2] = struct.pack(" Date: Sun, 1 Dec 2024 12:11:07 -0500 Subject: [PATCH 2/5] fixed sequence number increment globally --- modules/groundside_scripts.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/modules/groundside_scripts.py b/modules/groundside_scripts.py index 23ab749b..c688d7ae 100644 --- a/modules/groundside_scripts.py +++ b/modules/groundside_scripts.py @@ -60,7 +60,6 @@ def send_ftp_command( target_component=connection.target_component, payload=ftp_payload, ) - seq_num += 1 vehicle = mavutil.mavlink_connection(CONNECTION_ADDRESS, baud=57600) @@ -82,6 +81,7 @@ def send_ftp_command( size=len(FILE_PATH), payload=FILE_PATH, ) +SEQ_NUM += 1 response = vehicle.recv_match(type="FILE_TRANSFER_PROTOCOL", blocking=True, timeout=TIMEOUT) if response is None: @@ -116,6 +116,7 @@ def send_ftp_command( size=CHUNK_SIZE, payload=b"", ) + SEQ_NUM += 1 response = vehicle.recv_match(type="FILE_TRANSFER_PROTOCOL", blocking=True, timeout=TIMEOUT) if response is None: @@ -145,6 +146,7 @@ def send_ftp_command( size=CHUNK_SIZE, payload=b"", ) + SEQ_NUM += 1 # Terminate read session send_ftp_command( From 230fd66e7a998ac6a150bf2862f2b051da95fe56 Mon Sep 17 00:00:00 2001 From: j444zhan Date: Sat, 1 Feb 2025 17:08:43 -0700 Subject: [PATCH 3/5] fixes to seq_num incrementation and function returning FTP_response object with all fields --- modules/mavlink/ftp_example.py | 211 +++++++++++++++++++++++++++++++++ 1 file changed, 211 insertions(+) create mode 100644 modules/mavlink/ftp_example.py diff --git a/modules/mavlink/ftp_example.py b/modules/mavlink/ftp_example.py new file mode 100644 index 00000000..98309a5a --- /dev/null +++ b/modules/mavlink/ftp_example.py @@ -0,0 +1,211 @@ +""" +Groundside scripts to receive GPS location messages +""" + +import struct +import sys +from enum import Enum +from pymavlink import mavutil + +# connection params +CONNECTION_ADDRESS = "tcp:127.0.0.1:14550" +TIMEOUT = 5.0 +DELAY_TIME = 1.0 + +# file path to read from +# 1. start up connection on mission planner +# 2. mavlink and establish write tcp connection +# 3. config menu -> MAVFtp -> simulation drone file paths +FILE_PATH = b"/@ROMFS/locations.txt" +SEQ_NUM = 0 + + +class Opcode(Enum): + """ + Opcodes for FTP commands + """ + + NONE = 0 + TERMINATE_SESSION = 1 + RESET_SESSION = 2 + LIST_DIRECTORY = 3 + OPEN_FILE_RO = 4 + READ_FILE = 5 + CREATE_FILE = 6 + WRITE_FILE = 7 + REMOVE_FILE = 8 + CREATE_DIRECTORY = 9 + REMOVE_DIRECTORY = 10 + OPEN_FILE_WO = 11 + TRUNCATE_FILE = 12 + RENAME = 13 + CALC_FILE_CRC32 = 14 + BURST_READ_FILE = 15 + # ERROR responses + ACK_RESPONSE = 128 + NAK_RESPONSE = 129 + + +class NakErrorCode(Enum): + """ + Error codes for FTP commands + """ + + NONE = 0 # No Error + FAIL = 1 # Unknown failure + FAIL_ERRNO = 2 # Command failed, Err number sent back in PayloadHeader.data[1] + INVALID_DATA_SIZE = 3 # Payload size is invalid + INVALID_SESSION = 4 # Session is not currently open + NO_SESSIONS_AVAILABLE = 5 # All available sessions are in use + EOF = 6 # Offset past end of file for ListDirectory and ReadFile commands + UNKNOWN_CMD = 7 # Unknown command / Opcode + FILE_EXISTS = 8 # File/Directory already exists + FILE_PROTECTED = 9 # File/Directory is write protected + FILE_NOT_FOUND = 10 # File/Directory is not found + + +def send_ftp_command( + connection: mavutil.mavlink_connection, + seq_num: int, + opcode: int, + req_opcode: int, + session: int, + offset: int, + size: int, + payload: bytes, +) -> None: + """ + Send an FTP command to the vehicle. + + Args: + connection (mavutil.mavlink_connection): MAVLink connection object. + session (int): Session ID. | index 2 | range 0-255. + opcode (int): FTP command opcode | index 3 | range 0-255. + size (int): Size of the payload. | index 4 | range 0-255. + req_opcode (int): Requested opcode. | index 5 | range 0-255. + offset (int): Offset in the file. | index 8-11. + payload (bytes): Payload data. | index 12-251. + """ + ftp_payload = bytearray(251) # ftp payload size + + # packing payload in file system + ftp_payload[0:2] = struct.pack(" Date: Sat, 1 Feb 2025 17:12:11 -0700 Subject: [PATCH 4/5] formatting change --- modules/mavlink/ftp_example.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/mavlink/ftp_example.py b/modules/mavlink/ftp_example.py index 98309a5a..07d038fa 100644 --- a/modules/mavlink/ftp_example.py +++ b/modules/mavlink/ftp_example.py @@ -44,7 +44,7 @@ class Opcode(Enum): # ERROR responses ACK_RESPONSE = 128 NAK_RESPONSE = 129 - + class NakErrorCode(Enum): """ From cae916937c620d0c1b44afeecfdecb83e659f64a Mon Sep 17 00:00:00 2001 From: j444zhan Date: Sat, 1 Feb 2025 17:25:36 -0700 Subject: [PATCH 5/5] deleted test file groundside_scripts.py --- modules/groundside_scripts.py | 162 ---------------------------------- 1 file changed, 162 deletions(-) delete mode 100644 modules/groundside_scripts.py diff --git a/modules/groundside_scripts.py b/modules/groundside_scripts.py deleted file mode 100644 index c688d7ae..00000000 --- a/modules/groundside_scripts.py +++ /dev/null @@ -1,162 +0,0 @@ -""" -Groundside scripts to receive GPS location messages -""" - -import struct -import sys -from pymavlink import mavutil - -# connection params -CONNECTION_ADDRESS = "tcp:127.0.0.1:14550" -TIMEOUT = 5.0 -DELAY_TIME = 1.0 - -# file path to read from -# 1. start up connection on mission planner -# 2. mavlink and establish write tcp connection -# 3. config menu -> MAVFtp -> simulation drone file paths -FILE_PATH = b"/@ROMFS/locations.txt" -SEQ_NUM = 0 - - -def send_ftp_command( - connection: mavutil.mavlink_connection, - seq_num: int, - opcode: int, - req_opcode: int, - session: int, - offset: int, - size: int, - payload: bytes, -) -> None: - """ - Send an FTP command to the vehicle. - - Args: - connection (mavutil.mavlink_connection): MAVLink connection object. - opcode (int): FTP command opcode. - req_opcode (int): Requested opcode. - session (int): Session ID. - offset (int): Offset in the file. - size (int): Size of the payload. - payload (bytes): Payload data. - """ - ftp_payload = bytearray(251) # ftp payload size - - # packing payload in file system - ftp_payload[0:2] = struct.pack("