diff --git a/en/services/ftp.md b/en/services/ftp.md index 2b1f1a292..de46f37f4 100644 --- a/en/services/ftp.md +++ b/en/services/ftp.md @@ -73,24 +73,25 @@ The opcodes that may be sent by the GCS (client) to the drone (server) are enume -| Opcode | Name | Description | -| ------------------------------- | ---------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| 0 | None | Ignored, always ACKed | -| 1 | TerminateSession | Terminates open Read `session`.
- Closes the file associated with (`session`) and frees the session ID for re-use. | -| 2 | ResetSessions | Terminates _all_ open read sessions.
- Clears all state held by the drone (server); closes all open files, etc.
- Sends an ACK reply with no data. | -| 3 | [ListDirectory](#list_directory) | List directory entry information (files, folders etc.) in ``, starting from a specified entry index (``).
- 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. | -| 4 | [OpenFileRO](#reading-a-file) | Opens file at `` for reading, returns ``
- The `path` is stored in the [payload](#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](#error_codes) . 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`. | -| 5 | [ReadFile](#reading-a-file-readfile) | Reads `` bytes from `` in ``.
- 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. | -| 6 | `CreateFile` | Creates file at `` for writing, returns ``.
- 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](#FileExists) if the `path` already exists).
- The file remains open after the operation, and must eventually be closed by `Reset` or `Terminate`. | -| 7 | `WriteFile` | Writes `` bytes to `` in ``.
- Sends an ACK reply with no data on success, otherwise a NAK packet with an error code. | -| 8 | [RemoveFile](#remove-file) | Remove file at ``.
- ACK reply with no data on success.
- NAK packet with [error information](#error_codes) on failure. | -| 9 | [CreateDirectory](#create-directory) | Creates directory at ``.
- Sends an ACK reply with no data on success, otherwise a NAK packet with an error code. | -| 10 | [RemoveDirectory](#remove-directory) | Removes directory at ``. The directory must be empty.
- Sends an ACK reply with no data on success, otherwise a NAK packet with an error code. | -| 11 | OpenFileWO | Opens file at `` for writing, returns ``.
- Opens the file (`path`) and allocates a _session number_. The file will be created if it does not exist. Equivalent UNIX flags: (O*CREAT | 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`. | -| 12 | [TruncateFile](#truncate-file) | Truncate file at `` to `` length.
- Sends an ACK reply with no data on success, otherwise a NAK packet with an error code. | -| 13 | Rename | Rename `` to ``.
- 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). | -| 14 | CalcFileCRC32 | Calculate CRC32 for file at ``.
- Sends an ACK reply with the checksum on success, otherwise a NAK packet with an error code. | -| 15 | [BurstReadFile](#reading-a-file-burstreadfile) | Burst-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](#ReadFile). | +| Opcode | Name | Description | +| ------------------------------------- | -------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| 0 | None | Ignored, always ACKed | +| 1 | TerminateSession | Terminates open Read `session`.
- Closes the file associated with (`session`) and frees the session ID for re-use. | +| 2 | ResetSessions | Terminates _all_ open read sessions.
- Clears all state held by the drone (server); closes all open files, etc.
- Sends an ACK reply with no data. | +| 3 | [ListDirectory](#list_directory) | List directory entry information (files, folders etc.) in ``, starting from a specified entry index (``).
- 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. | +| 4 | [OpenFileRO](#reading-a-file) | Opens file at `` for reading, returns ``
- The `path` is stored in the [payload](#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](#error_codes) . 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`. | +| 5 | [ReadFile](#reading-a-file-readfile) | Reads `` bytes from `` in ``.
- 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. | +| 6 | `CreateFile` | Creates file at `` for writing, returns ``.
- 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](#FileExists) if the `path` already exists).
- The file remains open after the operation, and must eventually be closed by `Reset` or `Terminate`. | +| 7 | `WriteFile` | Writes `` bytes to `` in ``.
- Sends an ACK reply with no data on success, otherwise a NAK packet with an error code. | +| 8 | [RemoveFile](#remove-file) | Remove file at ``.
- ACK reply with no data on success.
- NAK packet with [error information](#error_codes) on failure. | +| 9 | [CreateDirectory](#create-directory) | Creates directory at ``.
- Sends an ACK reply with no data on success, otherwise a NAK packet with an error code. | +| 10 | [RemoveDirectory](#remove-directory) | Removes directory at ``. The directory must be empty.
- Sends an ACK reply with no data on success, otherwise a NAK packet with an error code. | +| 11 | OpenFileWO | Opens file at `` for writing, returns ``.
- Opens the file (`path`) and allocates a _session number_. The file will be created if it does not exist. Equivalent UNIX flags: (O*CREAT | 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`. | +| 12 | [TruncateFile](#truncate-file) | Truncate file at `` to `` length.
- Sends an ACK reply with no data on success, otherwise a NAK packet with an error code. | +| 13 | Rename | Rename `` to ``.
- 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). | +| 14 | CalcFileCRC32 | Calculate CRC32 for file at ``.
- Sends an ACK reply with the checksum on success, otherwise a NAK packet with an error code. | +| 15 | [BurstReadFile](#reading-a-file-burstreadfile) | Burst-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](#ReadFile). | +| 16 | [ListDirectoryWithTime](#list_directory_with_time) | List directory entry information as for [ListDirectory](#ListDirectory), but with each entry additionally including its last-modification time. Lets a GCS fetch timestamps without downloading file contents.
- A server that does not implement this command NAKs with [UnknownCommand](#UnknownCommand); clients should then fall back to [ListDirectory](#ListDirectory). | 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). @@ -451,6 +452,41 @@ The GCS should create a timeout after the `ListDirectory` command is sent and re The drone may also [NAK](#error_codes) 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. +### List Directory with Timestamps {#list_directory_with_time} + +[ListDirectoryWithTime](#ListDirectoryWithTime) works exactly like [ListDirectory](#list_directory), but each returned entry additionally includes its last-modification time. +This allows a GCS to display or compare timestamps (e.g. to show the most recent log, or to detect which files have changed), without having to download file contents. + +::: info +This is a separate opcode rather than a change to [ListDirectory](#list_directory) so that existing clients and servers keep working. +A client that needs timestamps uses `ListDirectoryWithTime`, and falls back to [ListDirectory](#ListDirectory) if the server NAKs with [UnknownCommand](#UnknownCommand). +::: + +The sequence of operations, offset-based paging, and [EOF](#EOF) termination are identical to [List Directory](#list_directory). +The only difference is the per-entry format returned in the ACK payload `data`. + +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**(kip)): + +```txt +\t\t\0 +``` + +The `modification_time` is the entry's last-modification time as a decimal ASCII string, in **seconds since the UNIX epoch (UTC)**. +If the modification time is not known — for example the file system does not store it, or the component has no real-time clock — the server must send `0`. + +For example, given five files named _TestFile1.xml_ to _TestFile5.xml_, the entries returned at offset 2 might look like: + +`FTestFile3.xml\t223\t1747459200\0FTestFile4.xml\t755568\t1746940800\0FTestFile5.xml\t11111\t0\0` + +(here the modification time of _TestFile5.xml_ is unknown). + +::: info +Only modification time is reported (not creation time). +POSIX `struct stat` — the interface exposed by most flight-stack file systems (e.g. NuttX) — has no portable creation-time field, so modification time is the only timestamp that can be reliably provided across backends. +::: + +The GCS should create a timeout after the `ListDirectoryWithTime` command is sent and resend the message as needed (and [described above](#timeouts)). + ### Create Directory The sequence of operations for creating a directory is shown below (assuming there are no timeouts and all operations/requests succeed).