MAVLinkFTPManager.h 10.8 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249
/****************************************************************************
 *
 *   (c) 2009-2018 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/


#pragma once

#include <QObject>
#include <QDir>
#include <QTimer>
#include <QQueue>

#include "UASInterface.h"
#include "QGCLoggingCategory.h"

#ifdef __GNUC__
#define PACKED_STRUCT( __Declaration__ ) __Declaration__ __attribute__((packed))
#else
#define PACKED_STRUCT( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) )
#endif


Q_DECLARE_LOGGING_CATEGORY(MAVLinkFTPManagerLog)

class Vehicle;

class MAVLinkFTPManager : public QObject
{
    Q_OBJECT

public:
    MAVLinkFTPManager(Vehicle* vehicle);

    /// These methods are only used for testing purposes.
    bool _sendCmdTestAck(void) { return _sendOpcodeOnlyCmd(kCmdNone, kCOAck); };
    bool _sendCmdTestNoAck(void) { return _sendOpcodeOnlyCmd(kCmdTestNoAck, kCOAck); };

    /// Timeout in msecs to wait for an Ack time come back. This is public so we can write unit tests which wait long enough
    /// for the MAVLinkFTPManager to timeout.
    static const int ackTimerTimeoutMsecs = 50;

    static const int ackTimerMaxRetries = 6;

    /// Downloads the specified file.
    ///     @param vehicleFilePath File to download from UAS, fully qualified path
    ///     @param downloadDir Local directory to download file to
    void downloadPath(const QString& vehicleFilePath, const QDir& downloadDir);

    /// Stream downloads the specified file.
    ///     @param from File to download from UAS, fully qualified path
    ///     @param downloadDir Local directory to download file to
    void streamPath(const QString& from, const QDir& downloadDir);

    /// Lists the specified directory. Emits listEntry signal for each entry, followed by listComplete signal.
    ///		@param dirPath Fully qualified path to list
    void listDirectory(const QString& dirPath);

    /// Upload the specified file to the specified location
    void uploadPath(const QString& toPath, const QFileInfo& uploadFile);

    /// Create a remote directory
    void createDirectory(const QString& directory);

signals:
    // Signals associated with the listDirectory method

    /// Signalled to indicate a new directory entry was received.
    void listEntry(const QString& entry);

    // Signals associated with all commands

    /// Signalled after a command has completed
    void commandComplete(void);

    /// Signalled when an error occurs during a command. In this case a commandComplete signal will
    /// not be sent.
    void commandError(const QString& msg);

    /// Signalled during a lengthy command to show progress
    ///     @param value Amount of progress: 0.0 = none, 1.0 = complete
    void commandProgress(int value);

public slots:
    void receiveMessage(mavlink_message_t message);

private slots:
    void _ackTimeout(void);

private:
    /// @brief This is the fixed length portion of the protocol data.
    /// 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
    PACKED_STRUCT(
            typedef struct _RequestHeader
    {
                uint16_t    seqNumber;      ///< sequence number for message
                uint8_t     session;        ///< Session id for read and write commands
                uint8_t     opcode;         ///< Command opcode
                uint8_t     size;           ///< Size of data
                uint8_t     req_opcode;     ///< Request opcode returned in kRspAck, kRspNak message
                uint8_t     burstComplete;  ///< Only used if req_opcode=kCmdBurstReadFile - 1: set of burst packets complete, 0: More burst packets coming.
                uint8_t     padding;        ///< 32 bit aligment padding
                uint32_t    offset;         ///< Offsets for List and Read commands
            }) RequestHeader;

    PACKED_STRUCT(
            typedef struct _Request
    {
                RequestHeader hdr;

                // We use a union here instead of just casting (uint32_t)&payload[0] to not break strict aliasing rules
                union {
                    // The entire Request must fit into the payload member of the mavlink_file_transfer_protocol_t structure. We use as many leftover bytes
                    // after we use up space for the RequestHeader for the data portion of the Request.
                    uint8_t data[sizeof(((mavlink_file_transfer_protocol_t*)0)->payload) - sizeof(RequestHeader)];

                    // File length returned by Open command
                    uint32_t openFileLength;

                    // Length of file chunk written by write command
                    uint32_t writeFileLength;
                };
            }) Request;

    enum Opcode
    {
        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 = 128,          ///< Ack response
        kRspNak,                ///< Nak response

        // Used for testing only, not part of protocol
        kCmdTestNoAck,          ///< ignored, ack not sent back, should timeout waiting for ack
    };

    /// @brief Error codes returned in Nak response PayloadHeader.data[0].
    enum ErrorCode
    {
        kErrNone,
        kErrFail,                   ///< Unknown failure
        kErrFailErrno,              ///< 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 OperationState
    {
        kCOIdle,		// not doing anything
        kCOAck,			// waiting for an Ack
        kCOList,		// waiting for List response
        kCOOpenRead,    // waiting for Open response followed by Read download
        kCOOpenBurst,   // waiting for Open response, followed by Burst download
        kCORead,		// waiting for Read response
        kCOBurst,		// waiting for Burst response
        kCOWrite,       // waiting for Write response
        kCOCreate,      // waiting for Create response
        kCOCreateDir,   // waiting for Create Directory response
    };

    bool _sendOpcodeOnlyCmd(uint8_t opcode, OperationState newOpState);
    void _setupAckTimeout(void);
    void _clearAckTimeout(void);
    void _emitErrorMessage(const QString& msg);
    void _emitListEntry(const QString& entry);
    void _sendRequest(Request* request);
    void _sendRequestNoAck(Request* request);
    void _fillRequestWithString(Request* request, const QString& str);
    void _openAckResponse(Request* openAck);
    void _downloadAckResponse(Request* readAck, bool readFile);
    void _listAckResponse(Request* listAck);
    void _createAckResponse(Request* createAck);
    void _writeAckResponse(Request* writeAck);
    void _writeFileDatablock(void);
    void _sendListCommand(void);
    void _sendResetCommand(void);
    void _closeDownloadSession(bool success);
    void _closeUploadSession(bool success);
    void _downloadWorker(const QString& vehicleFilePath, const QDir& downloadDir, bool readFile);
    void _requestMissingData();

    static QString errorString(uint8_t errorCode);

    OperationState  _currentOperation = kCOIdle;              ///< Current operation of state machine
    QTimer          _ackTimer;                      ///< Used to signal a timeout waiting for an ack
    int             _ackNumTries = 0;                   ///< current number of tries

    Vehicle*        _vehicle = nullptr;
    LinkInterface*  _dedicatedLink = nullptr; ///< Link to use for communication

    Request  _lastOutgoingRequest; ///< contains the last outgoing packet

    unsigned    _listOffset;    ///< offset for the current List operation
    QString     _listPath;      ///< path for the current List operation

    uint8_t     _activeSession = 0;             ///< currently active session, 0 for none

    uint32_t    _readOffset;                ///< current read offset

    uint32_t    _writeOffset;               ///< current write offset
    uint32_t    _writeSize;                 ///< current write data size
    uint32_t    _writeFileSize;             ///< Size of file being uploaded
    QByteArray  _writeFileAccumulator;      ///< Holds file being uploaded

    struct MissingData {
        uint32_t offset;
        uint32_t size;
    };
    uint32_t    _downloadOffset;            ///< current download offset
    uint32_t    _missingDownloadedBytes = 0;    ///< number of missing bytes for burst download
    QQueue<MissingData> _missingData;       ///< missing chunks of downloaded file (for burst downloads)
    bool        _downloadingMissingParts = false;   ///< true if we are currently downloading missing parts
    QByteArray  _readFileAccumulator;       ///< Holds file being downloaded
    QDir        _readFileDownloadDir;       ///< Directory to download file to
    QString     _readFileDownloadFilename;  ///< Filename (no path) for download file
    uint32_t    _downloadFileSize;          ///< Size of file being downloaded

    uint8_t     _systemIdQGC = 0;               ///< System ID for QGC
    uint8_t     _systemIdServer = 0;            ///< System ID for server

    // We give MockLinkFileServer friend access so that it can use the data structures and opcodes
    // to build a mock mavlink file server for testing.
    friend class MockLinkFileServer;
};