File Transfer Protocol (FTP)

The File Transfer Protocol (FTP) enables file transfer over MAVLink. It supports common FTP operations like: reading, truncating, writing, removing and creating files, listing and removing directories.

MAVLink FTP implementation closely follows the design of the original internet FTP protocol in terms of the message structure, sequences, and the supported opcodes/operations. Developers can read the Internet protocol RFCs to understand MAVLink FTP.

The protocol follows a client-server pattern, where all commands are sent by the GCS (client), and the Drone (server) responds either with an ACK containing the requested information, or a NAK containing an error. The GCS sets a timeout after most commands, and may resend the command if it is triggered. The drone must re-send its response if a request with the same sequence number is received.

All messages (commands, ACK, NAK) are exchanged inside FILE_TRANSFER_PROTOCOL messages. This message type definition is minimal, with fields for specifying the target network, system and component, and for an "arbitrary" variable-length payload.

The different commands and other information required to implement the protocol are encoded within in the FILE_TRANSFER_PROTOCOL payload. This topic explains the encoding, packing format, commands and errors, and the order in which the commands are sent to implement the core FTP functionality.

Protocol Discovery

FTP (v1) is supported if the AUTOPILOT_VERSION.capability field has the MAV_PROTOCOL_CAPABILITY_FTP flag set.

This flag should only be set by a MAVLink component that supports the specific version of the protocol defined in this document.

The encoding and content of the FILE_TRANSFER_PROTOCOL payload field are not mandated by the specification, and other encoding schemes might be used, for example, in private networks. If you have implemented a private encoding or different version you must not set the MAV_PROTOCOL_CAPABILITY_FTP flag.

Payload Format

The FILE_TRANSFER_PROTOCOL payload is encoded with the information required for the various FTP messages. This includes fields for holding the command that is being sent, the sequence number of the current FTP message (for multi-message data transfers), the size of information in the data part of the message etc.

Readers will note that the FTP payload format is very similar to the packet format used for serializing MAVLink itself.

Below is the over-the-wire format for the payload part of the FILE_TRANSFER_PROTOCOL message on PX4/QGroundControl.

FILE_TRANSFER_PROTOCOL Payload format - QGC

Byte IndexC versionContentValueExplanation
0 to 1uint16_t seq_numberSequence number for message0 - 65535All new messages between the GCS and drone iterate this number. Re-sent commands/ACK/NAK should use the previous response's sequence number.
2uint8_t sessionSession id0 - 255Session id for read/write operations (the server may use this to reference the file handle and information about the progress of read/write operations).
3uint8_t opcodeOpCode (id)0 - 255Ids for particular commands and ACK/NAK messages.
4uint8_t sizeSize0 - 255Depends on OpCode. For Reads/Writes this is the size of the data transported. For NAK it is the number of bytes used for error information (1 or 2).
5uint8_t req_opcodeRequest OpCode0 - 255OpCode (of original message) returned in an ACK or NAK response.
6uint8_t burst_completeBurst complete0, 1Code to indicate if a burst is complete. 1: set of burst packets complete, 0: More burst packets coming.
- Only used if req_opcode is BurstReadFile.
7uint8_t paddingPadding32 bit alignment padding.
8 to 11uint32_t offsetContent offsetOffsets into data to be sent for ListDirectory and ReadFile commands.
12 to (max) 251uint8_t data[]DataCommand/response data. Varies by OpCode. This contains the path for operations that act on a file or directory. For an ACK for a read or write this is the requested information. For an ACK for a OpenFileRO operation this is the size of the file that was opened. For a NAK the first byte is the error code and the (optional) second byte may be an error number.

OpCodes/Command

The opcodes that may be sent by the GCS (client) to the drone (server) are listed below.

OpcodeNameDescription
0NoneIgnored, always ACKed
1TerminateSessionTerminates open Read session.
- Closes the file associated with (session) and frees the session ID for re-use.
2ResetSessionsTerminates all open read sessions.
- Clears all state held by the drone (server); closes all open files, etc.
- Sends an ACK reply with no data.
3ListDirectoryList directory entry information (files, folders etc.) in <path>, starting from a specified entry index (<offset>).
- Response is an ACK packet with one or more entries on success, otherwise a NAK packet with an error code.
- Completion is indicated by a NACK with EOF in response to a requested index (offset) beyond the list of entries.
- The directory is closed after the operation, so this leaves no state on the server.
4OpenFileROOpens file at <path> for reading, returns <session>
- The path is stored in the payload data. The drone opens the file (path) and allocates a session number. The file must exist.
- An ACK packet must include the allocated session and the data size of the file to be opened (size)
- A NAK packet must contain error information . Typical error codes for this command are NoSessionsAvailable, FileExists.
- The file remains open after the operation, and must eventually be closed by Reset or Terminate.
5ReadFileReads <size> bytes from <offset> in <session>.
- Seeks to (offset) in the file opened in (session) and reads (size) bytes into the result buffer.
- Sends an ACK packet with the result buffer on success, otherwise a NAK packet with an error code. For short reads or reads beyond the end of a file, the (size) field in the ACK packet will indicate the actual number of bytes read.
- Reads can be issued to any offset in the file for any number of bytes, so reconstructing portions of the file to deal with lost packets should be easy.
- For best download performance, try to keep two Read packets in flight.
6CreateFileCreates file at <path> for writing, returns <session>.
- Creates the file (path) and allocates a session number. All parent directories must exist. If the file already existed, then this call will truncate it. Equivalent UNIX flags: (O_CREAT | O_TRUNC | O_WRONLY)
- Sends an ACK packet with the allocated session number on success, or a NAK packet with an error code on error (i.e. FileExists if the path already exists).
- The file remains open after the operation, and must eventually be closed by Reset or Terminate.
7WriteFileWrites <size> bytes to <offset> in <session>.
- Sends an ACK reply with no data on success, otherwise a NAK packet with an error code.
8RemoveFileRemove file at <path>.
- ACK reply with no data on success.
- NAK packet with error information on failure.
9CreateDirectoryCreates directory at <path>.
- Sends an ACK reply with no data on success, otherwise a NAK packet with an error code.
10RemoveDirectoryRemoves directory at <path>. The directory must be empty.
- Sends an ACK reply with no data on success, otherwise a NAK packet with an error code.
11OpenFileWOOpens file at <path> for writing, returns <session>.
- Opens the file (path) and allocates a session number. The file will be created if it does not exist. Equivalent UNIX flags: (OCREAT | O_WRONLY)
- Sends an ACK packet with the allocated _session number
on success, otherwise a NAK packet with an error code.
- The file remains open after the operation, and must eventually be closed by Reset or Terminate.
12TruncateFileTruncate file at <path> to <offset> length.
- Sends an ACK reply with no data on success, otherwise a NAK packet with an error code.
13RenameRename <path1> to <path2>.
- Sends an ACK reply the no data on success, otherwise a NAK packet with an error code (i.e. if the source path does not exist).
14CalcFileCRC32Calculate CRC32 for file at <path>.
- Sends an ACK reply with the checksum on success, otherwise a NAK packet with an error code.
15BurstReadFileBurst-read parts of a file. Messages in the burst are streamed (without ACK) until the burst is complete (as indicated by the field burst_complete being set to 1). Parts of a burst that are dropped may be fetched using ReadFile.

The drone (server) will respond with/send the following opcodes for any of the above messages (ACK response on success or a NAK in the event of an error).

OpcodeNameDescription
128ACKACK response.
129NAKNAK response.

Notes:

  • An ACK response may additionally return requested data in the payload (e.g. OpenFileRO returns the session and file size, ReadFile returns the requested file data, etc.).
  • The NAK response includes error information in the payload data.

NAK Error Information

NAK responses must include one of the errors codes listed below in the payload data[0] field.

An appropriate error code must be used if one is defined. If no appropriate error code exists, the Drone (server) may respond with Fail or FailErrno.

If the error code is FailErrno, then data[1] must additionally contain an error number. This error number is a file-system specific error code (understood by the server).

The payload size field must be set to either 1 or 2, depending on whether or not FailErrno is specified.

These are errors. Normally if the GCS receives an error it should not attempt to continue the FTP operation, but instead return to an idle state.

ErrorNameDescription
0NoneNo error
1FailUnknown failure
2FailErrnoCommand failed, Err number sent back in PayloadHeader.data[1]. This is a file-system error number understood by the server operating system.
3InvalidDataSizePayload size is invalid
4InvalidSessionSession is not currently open
5NoSessionsAvailableAll available sessions are already in use.
6EOFOffset past end of file for ListDirectory and ReadFile commands.
7UnknownCommandUnknown command / opcode
8FileExistsFile/directory already exists
9FileProtectedFile/directory is write protected
10FileNotFoundFile/directory not found

Timeouts/Resending

The GCS (client) starts a timeout after most commands are sent (these are cleared if an ACK/NAK is received).

Timeouts may not be set for some messages. For example, a timeout need not set for ResetSessions as the message should always succeed.

If a timeout activates either the command or its response is assumed to have been lost, and the command should be re-sent with the same sequence number etc. A number of retries are allowed, after which the GCS should fail the whole download and reset to an idle state.

If the drone (client) receives a message with the same sequence number then it assumes that its ACK/NAK response was lost. In this case it should resend the response (the sequence number is not iterated, because it is as though the previous response was not sent).

The drone has no timeout mechanism; it only ever responds to commands and does not expect any responses.

GCS recommended settings:

  • ACK/NAK timeout: 50 milliseconds
  • Command retries: 6

FTP Operations

Reading a File (ReadFile)

After opening a file session, ReadFile is called to request a message sized chunk of the file, which is then returned to the client in an ACK message. The process is repeated at different offsets until the whole file has been retrieved. The file session is then closed.

Burst reading a file is a (generally) faster alternative to this approach.

The sequence of operations for downloading (reading) a file using [ReadFile] is shown below. This assumes that there are no timeouts and all operations/requests succeed.

Mermaid Sequence: Reading a File

The sequence of operations is:

  1. GCS (client) sends OpenFileRO command specifying the file path to open.
    • The payload must specify: data[0]= file path string, size=length of file path string.
  2. Drone (server) responds with either
    • ACK on success. The payload must specify fields: session = file session id, size = 4, data = length of file that has been opened.
    • NAK with error information, e.g. NoSessionsAvailable, FileExists. The GCS may cancel the operation, depending on the error.
  3. GCS sends ReadFile commands to download a chunk of data from the file.
    • The payload must specify: session=current session, size=size of data to read, offset= position in data to start reading
  4. Drone responds to each message with either
    • ACK on success. The payload fields are: data = data chunk requested, size = size of data in the data field.
    • NAK on failure with error information.
  5. The ReadFile/ACK sequence above is repeated at different offsets to download the whole file.
    • Eventually the GCS will (must) request an offset past the end of the file.
    • The Drone will return a NAK with error code EOF. The GCS uses this message to recognise the download is complete.
  6. GCS sends TerminateSession to close the file. The drone should send an ACK/NAK, but this may (generally speaking) be ignored by the GCS.

The GSC should create a timeout after OpenFileRO and ReadFile commands are sent and resend the messages as needed (and described above). A timeout is not set for TerminateSession (the server may ignore failure of the command or the ACK).

Reading a File (BurstReadFile)

After opening a file for reading, it is read in "bursts". Each burst delivers a part of the file as a stream of messages. The last message in the burst is indicated by setting burst_complete=1 (without any ACKs).

The client tracks the recieved chunks. On completion of the burst (or the file), if there are any missing parts of the file it can request them using either another burst or using ReadFile.

Burst read is a (generally) faster alternative to using ReadFile to read a file. This is because fewer messages are sent and need to be waited on.

The sequence of operations for a burst read is shown below (assuming there are no timeouts and all operations/requests succeed).

Mermaid Sequence: Burst read file

The sequence of operations is:

  1. GCS (client) sends OpenFileRO command specifying the file path to open.
    • The payload must specify: data[0]= file path string, size=length of file path string.
  2. Drone (server) responds with either
    • ACK on success. The payload must specify fields: session = file session id, size = 4, data = length of file that has been opened.
    • NAK with error information, e.g. NoSessionsAvailable, FileExists. The GCS may cancel the operation, depending on the error.
  3. Client (i.e. GCS) sends BurstReadFile command specifying the part of the file that it wants to get from an offset to the end, along with the default size of each burst payload.
    • The payload must specify: session: the current session id, offset = offset in file of start of burst, size= default length of payload in burst responses, data is ignored.
  4. Server (drone) responds with either
    • ACK on success. The payload must specify fields: session = file session id, size = 4, data = length of file in burst.
    • NAK with error information. The client may cancel the operation, depending on the error.
  5. Server sends stream of BurstReadFile data to client (without ACK) until the whole burst is sent, or a server-defined burst size limit is reached.
    • The payload must specify: session=current session, size=size of data to read per burst message (max equal to payload size = 239), offset= position in original data of current chunk.
    • The payload must specify burst_complete=0 for all chunks, except the last one, which must set burst_complete=1.
  6. The client must maintain its own record of the received (and missing) chunks. It may request any missing chunks at either the end of a burst or at the end of the file. Missing chunks can be requested using ReadFile.
  7. Client sends TerminateSession to close the file once all the chunks have been downloaded The server should send an ACK/NAK, but this may (generally speaking) be ignored by the client.

The client should create a timeout while waiting for a new BurstReadFile, and on expiry may request missing parts of the file using either BurstReadFile or ReadFile A timeout is not set for TerminateSession (the server may ignore failure of the command or the ACK).

Uploading a File

The sequence of operations for uploading a file to the drone, assuming there are no timeouts and all operations/requests succeed, is shown below.

Mermaid Sequence: Uploading a file

The sequence of operations is:

  1. GCS (client) sends CreateFile command specifying the file path where the file is to be uploaded.
    • The payload must specify: data[0]= target file path string, size=length of file path string.
  2. Drone (server) attempts to create the file, and responds with either
    • ACK on success. The payload must specify fields: session = new file session id, size = 0.
    • NAK with error information.
      • The GCS should cancel the whole operation on error.
      • If there is a sequence error at this stage the GCS should send a command to ResetSessions
  3. GCS sends WriteFile commands to upload a chunk of data to the Drone.
    • The payload must specify: session=current session id, data=file chunk,size=length of data, offset= offset of data to write
  4. Drone responds to each message with either
    • ACK on success. The payload fields are: size = 0.
    • NAK on failure with error information.
      • The GCS should cancel the whole upload operation by sending a command to ResetSessions if there is an NAK.
  5. The WriteFile/ACK sequence above is repeated at different offsets to upload the whole file. Once the GCS determines that the upload is complete it moves to the next step.
  6. GCS sends TerminateSession to close the file. The drone should send an ACK/NAK, but this may (generally speaking) be ignored by the GCS.

The GSC should create a timeout after CreateFile and WriteFile commands are sent, and resend the messages as needed (and described above). A timeout is not set for TerminateSession (the server may ignore failure of the command or the ACK).

PX4 and QGroundControl implement this slightly differently than outlined above. The implementation only has a single session (id=0) so only a single operation can be active at a time. As a result, this operation should only be started if no other operation is active. The drone expects that the session id will be set to zero by the sender of CreateFile. Last of all, the GCS sends ResetSessions rather than TerminateSession. While you can send either if talking to PX4, if the protocol is implemented elsewhere calling ResetSessions may break other communications.

Remove File

RemoveFile handling is implemented in PX4 but not in QGroundControl. GCS behaviour is therefore not fully defined/tested.

The sequence of operations for removing a file is shown below (assuming there are no timeouts and all operations/requests succeed).

Mermaid Sequence: Removing a file

The sequence of operations is:

  1. GCS sends RemoveFile command specifying the full path of the file to be deleted.
    • The payload must specify: data[0]= file path string, size=length of file path string.
  2. Drone attempts to delete file, and responds to the message with either:
    • ACK on success, containing payload size=0 (i.e. no data).
    • NAK on failure, with error information.
    • The drone must clean up any resources associated with the request after sending the response.

The GSC should create a timeout after the RemoveFile command is sent and resend the message as needed (and described above).

Truncate File

The sequence of operations for truncating a file is shown below (assuming there are no timeouts and all operations/requests succeed).

TruncateFile handling is implemented in PX4 but not in QGroundControl. GCS behaviour is therefore not fully defined/tested.

Mermaid Sequence: Truncate file

The sequence of operations is:

  1. GCS sends TruncateFile command specifying file to truncate and the offset for truncation.
    • The payload must specify: data[0]= file path string, size = length of file path string, offset = truncation point in file (amount of data to keep).
  2. Drone attempts to truncate file, and responds to the message with either:
    • ACK on success, containing payload size=0 (i.e. no data).
      • The request should succeed if the offset is the same as the file size, and may be attempted if the offset is zero (i.e. truncate whole file).
    • NAK on failure, with error information.
      • The request should fail if the offset is 0 (truncate whole file) and for normal file system errors.
    • The drone must clean up any resources associated with the request after sending the response.

The GSC should create a timeout after the TruncateFile command is sent and resend the message as needed (and described above).

List Directory

The sequence of operations for getting a directory listing is shown below (assuming there are no timeouts and all operations/requests succeed).

Mermaid Sequence: List Directory

The sequence of operations is:

  1. GCS sends ListDirectory command specifying a directory path and the index of an entry.
    • The payload must specify:
      • data[0] = file path
      • size = length of path string
      • offset = The index of the first entry to get (0 for first entry, 1 for second, etc.).
  2. Drone responds with an ACK containing one or more entries (the first entry is the one specified in request offset field).
    • The payload must specify:
      • data[0] = Information for one or more (sequential) entries, starting at the requested entry index (offset). Each entry is separated with a null terminator (\0), and has the following format (where type is one of the letters F(ile), D(irectory), S(skip))
        <type><file_or_folder_name>\t<file_size_in_bytes>\0
        
        For example, given five files named TestFile1.xml to TestFile5.xml, the entries returned at offset 2 might look like: FTestFile3.xml\t223\0FTestFile4.xml\t755568\0FTestFile5.xml\t11111\0
      • size = The size of the data.
  3. The operation is then repeated at different offsets to download the whole directory listing.

    The offset for each request will depend on how many entries were returned by the previous request(s).

  4. The operation completes when the GCS requests an entry index (offset) greater than or equal to the number of entries. In this case the drone responds with a NAK containing EOF (end of file).

The GSC should create a timeout after the ListDirectory command is sent and resend the message as needed (and described above).

The drone may also NAK with an unexpected error. Generally errors are unrecoverable, and the drone must clean up all resources (i.e. close file handles) associated with the request after sending the NAK.

Create Directory

The sequence of operations for creating a directory is shown below (assuming there are no timeouts and all operations/requests succeed). Note that this operation will fail if the directory is not empty.

Mermaid Sequence: Create Directory

The sequence of operations is:

  1. GCS sends CreateDirectory command specifying the full path of the directory to be created.
    • The payload must specify: data[0]= directory path string, size=length of directory path string.
  2. Drone attempts to create directory, and responds to the message with either:
    • ACK on success, containing payload size=0 (i.e. no data).
    • NAK on failure, with error information.
    • The drone must clean up any resources associated with the request after sending the response.

The GSC should not create timeouts or handle the NAK case (other than to report an error to the user).

Remove Directory

RemoveDirectory handling is implemented in PX4 but not in QGroundControl. GCS behaviour is therefore not fully defined/tested.

The sequence of operations for removing a directory is shown below (assuming there are no timeouts and all operations/requests succeed). Note that this operation will fail if the directory is not empty.

Mermaid Sequence: Remove directory

The sequence of operations is:

  1. GCS sends RemoveDirectory command specifying the full path of the directory to be deleted.
    • The payload must specify: data[0]= directory path string, size=length of directory path string.
  2. Drone attempts to delete directory, and responds to the message with either:
    • ACK on success, containing payload size=0 (i.e. no data).
    • NAK on failure, with error information.
    • The drone must clean up any resources associated with the request after sending the response.

The GSC should create a timeout after the RemoveDirectory command is sent and resend the message as needed (and described above).

Implementations

The FTP v1 Protocol has been implemented (at least) in PX4, ArduPilot, QGroundControl and MAVSDK. Those implementations can be used in your own code within the terms of their software licenses.

PX4 Implementation:

QGroundControl implementation:

Everything is run by the master (QGC in this case); the slave simply responds to packets in order as they arrive. There’s buffering in the server for a little overlap (two packets in the queue at a time). This is a tradeoff between memory and link latency which may need to be reconsidered at some point.

The MAVLink receiver thread copies an incoming request verbatim from the MAVLink buffer into a request queue, and queues a low-priority work item to handle the packet. This avoids trying to do file I/O on the MAVLink receiver thread, as well as avoiding yet another worker thread. The worker is responsible for directly queuing replies, which are sent with the same sequence number as the request.

The implementation on PX4 only supports a single session.

CRC32 Implementation

The CRC32 algorithm used by MAVLink FTP is described in MAVLink CRCs.

Resources to be downloaded using MAVLink FTP can be referenced using the following URL-like format:

mftp://[;comp=<id>]<path>

Where:

  • path: the location of the resource on the target component.
  • id: target component ID of the component hosting the resource. The [;comp=<id>] part is optional (if omitted, the resource is downloaded from the current component). It should be specified if the request must be redirected

For example:

  • A GCS connected to an autopilot might download a file using the following URL:
    ## FTP resource 'camera.xml' from current component
    mftp://camera.xml
    
  • A GCS connected to an autopilot through a companion computer might host the metadata on the companion (e.g. due to lack of flash space, faster download or if there's a central MAVFTP server on the vehicle), so it would need to specify the component ID of the component running on the companion (e.g. 100 for the camera), so that the request is redirected:
    ## FTP resource '/info/version.json' from component with id 100
    mftp://[;comp=100]/info/version.json
    

results matching ""

    No results matching ""