FTPManager.h 4.9 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
/****************************************************************************
 *
 * (c) 2009-2020 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"
#include "QGCMAVLink.h"

Q_DECLARE_LOGGING_CATEGORY(FTPManagerLog)

class Vehicle;

class FTPManager : public QObject
{
    Q_OBJECT
28 29

    friend class Vehicle;
30 31 32 33 34 35 36 37 38 39 40 41
    
public:
    FTPManager(Vehicle* vehicle);

	/// Downloads the specified file.
    ///     @param from     File to download from vehicle, fully qualified path. May be in the format mavlinkftp://...
    ///     @param toDir    Local directory to download file to
    /// @return true: download has started, false: error, no download
    /// Signals downloadComplete, commandError, commandProgress
    bool download(const QString& from, const QString& toDir);

signals:
42
    void downloadComplete(const QString& file, const QString& errorMsg);
43 44 45 46 47 48 49 50 51 52 53 54 55
    
    // Signals associated with all commands
    
    /// Signalled after a command has completed
    void commandComplete(void);
    
    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);
	
private slots:
56
    void _ackOrNakTimeout(void);
57 58

private:
59 60 61 62 63 64 65 66 67 68
    typedef void (FTPManager::*StateBeginFn)            (void);
    typedef void (FTPManager::*StateAckNakFn)    (const MavlinkFTP::Request* ackOrNak);
    typedef void (FTPManager::*StateTimeoutFn)          (void);

    typedef struct {
        StateBeginFn    beginFn;
        StateAckNakFn   ackNakFn;
        StateTimeoutFn  timeoutFn;
    } StateFunctions_t;

69
    typedef struct  {
70
        uint32_t offset;
71
        uint32_t cBytesMissing;
72 73
    } MissingData_t;

74 75 76
    typedef struct {
        uint8_t                 sessionId;
        uint32_t                expectedOffset;         ///< offset which should be coming next
77
        uint32_t                bytesWritten;
78 79
        QList<MissingData_t>    rgMissingData;
        QString                 fullPathOnVehicle;      ///< Fully qualified path to file on vehicle
80 81 82 83 84 85 86
        QDir                    toDir;                  ///< Directory to download file to
        QString                 fileName;               ///< Filename (no path) for download file
        uint32_t                fileSize;               ///< Size of file being downloaded
        QFile                   file;
        int                     retryCount;

        void reset() {
87 88 89 90 91 92 93 94
            sessionId       = 0;
            expectedOffset  = 0;
            bytesWritten    = 0;
            retryCount      = 0;
            fileSize        = 0;
            fullPathOnVehicle.clear();
            fileName.clear();
            rgMissingData.clear();
95 96
            file.close();
        }
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
    } DownloadState_t;


    void    _mavlinkMessageReceived     (const mavlink_message_t& message);
    void    _startStateMachine          (void);
    void    _advanceStateMachine        (void);
    void    _openFileROBegin            (void);
    void    _openFileROAckOrNak         (const MavlinkFTP::Request* ackOrNak);
    void    _openFileROTimeout          (void);
    void    _burstReadFileBegin         (void);
    void    _burstReadFileAckOrNak      (const MavlinkFTP::Request* ackOrNak);
    void    _burstReadFileTimeout       (void);
    void    _fillMissingBlocksBegin     (void);
    void    _fillMissingBlocksAckOrNak  (const MavlinkFTP::Request* ackOrNak);
    void    _fillMissingBlocksTimeout   (void);
    void    _resetSessionsBegin         (void);
    void    _resetSessionsAckOrNak      (const MavlinkFTP::Request* ackOrNak);
    void    _resetSessionsTimeout       (void);
    QString _errorMsgFromNak            (const MavlinkFTP::Request* nak);
    void    _sendRequestExpectAck       (MavlinkFTP::Request* request);
    void    _downloadCompleteNoError    (void) { _downloadComplete(QString()); }
    void    _downloadComplete           (const QString& errorMsg);
    void    _emitErrorMessage           (const QString& msg);
    void    _fillRequestDataWithString(MavlinkFTP::Request* request, const QString& str);
    void    _fillMissingBlocksWorker    (bool firstRequest);
    void    _burstReadFileWorker        (bool firstRequest);
123

124 125 126 127 128 129 130 131 132
    Vehicle*                _vehicle;
    QList<StateFunctions_t> _rgStateMachine;
    DownloadState_t         _downloadState;
    QTimer                  _ackOrNakTimeoutTimer;
    int                     _currentStateMachineIndex   = -1;
    uint16_t                _expectedIncomingSeqNumber  = 0;
    
    static const int _ackOrNakTimeoutMsecs  = 1000;
    static const int _maxRetry              = 3;
133 134
};