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