QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
FTPManager.h
Go to the documentation of this file.
1#pragma once
2
3#include "MAVLinkFTP.h"
4
5#include <QtCore/QObject>
6#include <QtCore/QDir>
7#include <QtCore/QFile>
8#include <QtCore/QTimer>
9class Vehicle;
10
11class FTPManager : public QObject
12{
13 Q_OBJECT
14
15 friend class Vehicle;
16
17public:
18 FTPManager(Vehicle* vehicle);
19
33 bool download(uint8_t fromCompId, const QString& fromURI, const QString& toDir, const QString& fileName="", bool checksize = true);
34
41 bool upload(uint8_t toCompId, const QString& toURI, const QString& fromFile);
42
49 bool listDirectory(uint8_t fromCompId, const QString& fromURI);
50
56 bool deleteFile(uint8_t fromCompId, const QString& fromURI);
57
60 void cancelDownload();
61
65
68 void cancelDelete();
69
72 void cancelUpload();
73
74 static constexpr const char* mavlinkFTPScheme = "mftp";
75
76signals:
77 void downloadComplete (const QString& file, const QString& errorMsg);
78 void uploadComplete (const QString& file, const QString& errorMsg);
79 void listDirectoryComplete (const QStringList& dirList, const QString& errorMsg);
80 void deleteComplete (const QString& file, const QString& errorMsg);
81
84 void commandProgress(float value);
85
86private slots:
87 void _ackOrNakTimeout(void);
88
89private:
90 typedef void (FTPManager::*StateBeginFn) (void);
91 typedef void (FTPManager::*StateAckNakFn) (const MavlinkFTP::Request* ackOrNak);
92 typedef void (FTPManager::*StateTimeoutFn) (void);
93
94 struct StateFunctions_t {
95 StateBeginFn beginFn;
96 StateAckNakFn ackNakFn;
97 StateTimeoutFn timeoutFn;
98 };
99
100 struct MissingData_t {
101 uint32_t offset;
102 uint32_t cBytesMissing;
103 };
104
105 struct DownloadState_t {
106 uint8_t sessionId;
107 uint32_t expectedOffset;
108 uint32_t bytesWritten;
109 QList<MissingData_t> rgMissingData;
110 QString fullPathOnVehicle;
111 QDir toDir;
112 QString fileName;
113 uint32_t fileSize;
114 QFile file;
115 int retryCount;
116 bool checksize;
117
118 bool inProgress() const { return fileSize > 0; }
119
120 void reset() {
121 sessionId = 0;
122 expectedOffset = 0;
123 bytesWritten = 0;
124 retryCount = 0;
125 fileSize = 0;
126 fullPathOnVehicle.clear();
127 fileName.clear();
128 rgMissingData.clear();
129 file.close();
130 }
131 };
132
133 struct ListDirectoryState_t {
134 uint8_t sessionId;
135 uint32_t expectedOffset;
136 QString fullPathOnVehicle;
137 QStringList rgDirectoryList;
138 int retryCount;
139
140 bool inProgress() const { return !fullPathOnVehicle.isEmpty(); }
141
142 void reset() {
143 sessionId = 0;
144 expectedOffset = 0;
145 fullPathOnVehicle.clear();
146 rgDirectoryList.clear();
147 retryCount = 0;
148 }
149 };
150
151 struct DeleteFileState_t {
152 QString fullPathOnVehicle;
153 int retryCount = 0;
154
155 bool inProgress() const { return !fullPathOnVehicle.isEmpty(); }
156
157 void reset() {
158 fullPathOnVehicle.clear();
159 retryCount = 0;
160 }
161 };
162
163 struct UploadState_t {
164 uint8_t sessionId;
165 uint32_t totalBytesSent;
166 uint32_t fileSize;
167 uint32_t lastChunkSize;
168 QFile file;
169 QString fullPathOnVehicle;
170 QString localFilePath;
171 int retryCount;
172 bool cancelled;
173
174 bool inProgress() const { return file.isOpen(); }
175
176 void reset() {
177 sessionId = 0;
178 totalBytesSent = 0;
179 fileSize = 0;
180 lastChunkSize = 0;
181 retryCount = 0;
182 cancelled = false;
183 fullPathOnVehicle.clear();
184 localFilePath.clear();
185 file.close();
186 }
187 };
188
189 void _mavlinkMessageReceived (const mavlink_message_t& message);
190 void _startStateMachine (void);
191 void _advanceStateMachine (void);
192 void _listDirectoryBegin (void);
193 void _listDirectoryAckOrNak (const MavlinkFTP::Request* ackOrNak);
194 void _listDirectoryTimeout (void);
195 void _openFileROBegin (void);
196 void _openFileROAckOrNak (const MavlinkFTP::Request* ackOrNak);
197 void _openFileROTimeout (void);
198 void _burstReadFileBegin (void);
199 void _burstReadFileAckOrNak (const MavlinkFTP::Request* ackOrNak);
200 void _burstReadFileTimeout (void);
201 void _fillMissingBlocksBegin (void);
202 void _fillMissingBlocksAckOrNak (const MavlinkFTP::Request* ackOrNak);
203 void _fillMissingBlocksTimeout (void);
204 void _resetSessionsBegin (void);
205 void _resetSessionsAckOrNak (const MavlinkFTP::Request* ackOrNak);
206 void _resetSessionsTimeout (void);
207 QString _errorMsgFromNak (const MavlinkFTP::Request* nak);
208 void _sendRequestExpectAck (MavlinkFTP::Request* request);
209 void _downloadCompleteNoError (void) { _downloadComplete(QString()); }
210 void _downloadComplete (const QString& errorMsg);
211 void _fillRequestDataWithString(MavlinkFTP::Request* request, const QString& str);
212 void _fillMissingBlocksWorker (bool firstRequest);
213 void _burstReadFileWorker (bool firstRequest);
214 void _listDirectoryWorker (bool firstRequest);
215 bool _parseURI (uint8_t fromCompId, const QString& uri, QString& parsedURI, uint8_t& compId);
216 void _listDirectoryCompleteNoError(void) { _listDirectoryComplete(QString()); }
217 void _listDirectoryComplete (const QString& errorMsg);
218 void _deleteFileBegin (void);
219 void _deleteFileAckOrNak (const MavlinkFTP::Request* ackOrNak);
220 void _deleteFileTimeout (void);
221 void _deleteCompleteNoError (void) { _deleteComplete(QString()); }
222 void _deleteComplete (const QString& errorMsg);
223
224 void _createFileBegin (void);
225 void _createFileAckOrNak (const MavlinkFTP::Request* ackOrNak);
226 void _createFileTimeout (void);
227 void _writeFileBegin (void);
228 void _writeFileAckOrNak (const MavlinkFTP::Request* ackOrNak);
229 void _writeFileTimeout (void);
230 void _writeFileWorker (bool firstRequest);
231 void _uploadFinalize (void);
232 void _uploadComplete (const QString& errorMsg);
233 void _terminateUploadSessionBegin(void);
234 void _terminateUploadSessionAckOrNak(const MavlinkFTP::Request* ackOrNak);
235 void _terminateUploadSessionTimeout(void);
236
237 void _terminateSessionBegin (void);
238 void _terminateSessionAckOrNak (const MavlinkFTP::Request* ackOrNak);
239 void _terminateSessionTimeout (void);
240 void _terminateComplete (void);
241
242 Vehicle* _vehicle;
243 uint8_t _ftpCompId = MAV_COMP_ID_AUTOPILOT1;
244 QList<StateFunctions_t> _rgStateMachine;
245 DownloadState_t _downloadState;
246 ListDirectoryState_t _listDirectoryState;
247 DeleteFileState_t _deleteState;
248 UploadState_t _uploadState;
249 QTimer _ackOrNakTimeoutTimer;
250 int _currentStateMachineIndex = -1;
251 uint16_t _expectedIncomingSeqNumber = 0;
252
253 static const int _ackOrNakTimeoutMsecs = 1000;
254 static const int _maxRetry = 3;
255
256public:
258 static constexpr int kTestAckTimeoutMs = 10;
260 static constexpr int kTestOperationMaxWaitMs = 5000;
261};
struct __mavlink_message mavlink_message_t
static constexpr int kTestAckTimeoutMs
Ack timeout used in unit tests (much shorter for faster tests)
Definition FTPManager.h:258
void cancelDownload()
bool listDirectory(uint8_t fromCompId, const QString &fromURI)
bool deleteFile(uint8_t fromCompId, const QString &fromURI)
bool upload(uint8_t toCompId, const QString &toURI, const QString &fromFile)
Definition FTPManager.cc:85
static constexpr const char * mavlinkFTPScheme
Definition FTPManager.h:74
void uploadComplete(const QString &file, const QString &errorMsg)
void cancelUpload()
static constexpr int kTestOperationMaxWaitMs
Maximum wait time for FTP operations in unit tests (generous for multi-packet transfers)
Definition FTPManager.h:260
void commandProgress(float value)
void downloadComplete(const QString &file, const QString &errorMsg)
void cancelListDirectory()
void deleteComplete(const QString &file, const QString &errorMsg)
void cancelDelete()
bool download(uint8_t fromCompId, const QString &fromURI, const QString &toDir, const QString &fileName="", bool checksize=true)
Definition FTPManager.cc:30
void listDirectoryComplete(const QStringList &dirList, const QString &errorMsg)