37 bool download(uint8_t fromCompId,
const QString& fromURI,
const QString& toDir,
const QString& fileName=
"",
bool checksize =
true);
45 bool upload(uint8_t toCompId,
const QString& toURI,
const QString& fromFile);
53 bool listDirectory(uint8_t fromCompId,
const QString& fromURI);
60 bool deleteFile(uint8_t fromCompId,
const QString& fromURI);
91 void _ackOrNakTimeout(
void);
94 typedef void (
FTPManager::*StateBeginFn) (void);
96 typedef void (
FTPManager::*StateTimeoutFn) (void);
98 struct StateFunctions_t {
100 StateAckNakFn ackNakFn;
101 StateTimeoutFn timeoutFn;
104 struct MissingData_t {
106 uint32_t cBytesMissing;
109 struct DownloadState_t {
111 uint32_t expectedOffset;
112 uint32_t bytesWritten;
113 QList<MissingData_t> rgMissingData;
114 QString fullPathOnVehicle;
122 bool inProgress()
const {
return fileSize > 0; }
130 fullPathOnVehicle.clear();
132 rgMissingData.clear();
137 struct ListDirectoryState_t {
139 uint32_t expectedOffset;
140 QString fullPathOnVehicle;
141 QStringList rgDirectoryList;
144 bool inProgress()
const {
return !fullPathOnVehicle.isEmpty(); }
149 fullPathOnVehicle.clear();
150 rgDirectoryList.clear();
155 struct DeleteFileState_t {
156 QString fullPathOnVehicle;
159 bool inProgress()
const {
return !fullPathOnVehicle.isEmpty(); }
162 fullPathOnVehicle.clear();
167 struct UploadState_t {
169 uint32_t totalBytesSent;
171 uint32_t lastChunkSize;
173 QString fullPathOnVehicle;
174 QString localFilePath;
178 bool inProgress()
const {
return file.isOpen(); }
187 fullPathOnVehicle.clear();
188 localFilePath.clear();
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);
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);
241 void _terminateSessionBegin (
void);
242 void _terminateSessionAckOrNak (
const MavlinkFTP::Request* ackOrNak);
243 void _terminateSessionTimeout (
void);
244 void _terminateComplete (
void);
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;
257 static const int _ackOrNakTimeoutMsecs = 1000;
258 static const int _maxRetry = 3;