|
Firmware
|
MAVLink remote file server. Support FTP like commands using MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL message. More...
#include <mavlink_ftp.h>
Public Types | |
| enum | Opcode : uint8_t { kCmdNone, kCmdTerminateSession, kCmdResetSessions, kCmdListDirectory, kCmdOpenFileRO, kCmdReadFile, kCmdCreateFile, kCmdWriteFile, kCmdRemoveFile, kCmdCreateDirectory, kCmdRemoveDirectory, kCmdOpenFileWO, kCmdTruncateFile, kCmdRename, kCmdCalcFileCRC32, kCmdBurstReadFile, kRspAck = 128, kRspNak } |
| Command opcodes. More... | |
| enum | ErrorCode : uint8_t { kErrNone, kErrFail, kErrFailErrno, kErrInvalidDataSize, kErrInvalidSession, kErrNoSessionsAvailable, kErrEOF, kErrUnknownCommand, kErrFailFileExists, kErrFailFileProtected } |
| Error codes returned in Nak response PayloadHeader.data[0]. More... | |
| typedef void(* | ReceiveMessageFunc_t) (const mavlink_file_transfer_protocol_t *ftp_req, void *worker_data) |
Public Member Functions | |
| MavlinkFTP (Mavlink *mavlink) | |
| void | send (const hrt_abstime t) |
| Handle sending of messages. More... | |
| void | handle_message (const mavlink_message_t *msg) |
| Handle possible FTP message. | |
| void | set_unittest_worker (ReceiveMessageFunc_t rcvMsgFunc, void *worker_data) |
| Sets up the server to run in unit test mode. More... | |
| struct | __attribute__ ((__packed__)) PayloadHeader |
| This is the payload which is in mavlink_file_transfer_protocol_t.payload. More... | |
| unsigned | get_size () |
Friends | |
| class | MavlinkFtpTest |
MAVLink remote file server. Support FTP like commands using MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL message.
| enum MavlinkFTP::ErrorCode : uint8_t |
Error codes returned in Nak response PayloadHeader.data[0].
| Enumerator | |
|---|---|
| kErrFail | Unknown failure. |
| kErrFailErrno | Command failed, errno sent back in PayloadHeader.data[1]. |
| kErrInvalidDataSize | PayloadHeader.size is invalid. |
| kErrInvalidSession | Session is not currently open. |
| kErrNoSessionsAvailable | All available Sessions in use. |
| kErrEOF | Offset past end of file for List and Read commands. |
| kErrUnknownCommand | Unknown command opcode. |
| kErrFailFileExists | File exists already. |
| kErrFailFileProtected | File is write protected. |
| enum MavlinkFTP::Opcode : uint8_t |
Command opcodes.
| Enumerator | |
|---|---|
| kCmdNone | ignored, always acked |
| kCmdTerminateSession | Terminates open Read session. |
| kCmdResetSessions | Terminates all open Read sessions. |
| kCmdListDirectory | List files in <path> from <offset> |
| kCmdOpenFileRO | Opens file at <path> for reading, returns <session> |
| kCmdReadFile | Reads <size> bytes from <offset> in <session> |
| kCmdCreateFile | Creates file at <path> for writing, returns <session> |
| kCmdWriteFile | Writes <size> bytes to <offset> in <session> |
| kCmdRemoveFile | Remove file at <path> |
| kCmdCreateDirectory | Creates directory at <path> |
| kCmdRemoveDirectory | Removes Directory at <path>, must be empty. |
| kCmdOpenFileWO | Opens file at <path> for writing, returns <session> |
| kCmdTruncateFile | Truncate file at <path> to <offset> length. |
| kCmdRename | Rename <path1> to <path2> |
| kCmdCalcFileCRC32 | Calculate CRC32 for file at <path> |
| kCmdBurstReadFile | Burst download session file. |
| kRspAck | Ack response. |
| kRspNak | Nak response. |
|
inline |
This is the payload which is in mavlink_file_transfer_protocol_t.payload.
This needs to be packed, because it's typecasted from mavlink_file_transfer_protocol_t.payload, which starts at a 3 byte offset, causing an unaligned access to seq_number and offset
< sequence number for message
< Session id for read and write commands
< Command opcode
< Size of data
< Request opcode returned in kRspAck, kRspNak message
< Only used if req_opcode=kCmdBurstReadFile - 1: set of burst packets complete, 0: More burst packets coming.
< 32 bit aligment padding
< Offsets for List and Read commands
< command data, varies by Opcode
| void MavlinkFTP::send | ( | const hrt_abstime | t | ) |
Handle sending of messages.
Call this regularly at a fixed frequency.
| t | current time |
| void MavlinkFTP::set_unittest_worker | ( | ReceiveMessageFunc_t | rcvMsgFunc, |
| void * | worker_data | ||
| ) |
Sets up the server to run in unit test mode.
| rcvmsgFunc | Function which will be called to handle outgoing mavlink messages. |
| worker_data | Data to pass to worker |
1.8.12