33 bool download(uint8_t fromCompId,
const QString& fromURI,
const QString& toDir,
const QString& fileName=
"",
bool checksize =
true);
41 bool upload(uint8_t toCompId,
const QString& toURI,
const QString& fromFile);
49 bool listDirectory(uint8_t fromCompId,
const QString& fromURI);
56 bool deleteFile(uint8_t fromCompId,
const QString& fromURI);
87 void _ackOrNakTimeout(
void);
90 typedef void (
FTPManager::*StateBeginFn) (void);
92 typedef void (
FTPManager::*StateTimeoutFn) (void);
94 struct StateFunctions_t {
96 StateAckNakFn ackNakFn;
97 StateTimeoutFn timeoutFn;
100 struct MissingData_t {
102 uint32_t cBytesMissing;
105 struct DownloadState_t {
107 uint32_t expectedOffset;
108 uint32_t bytesWritten;
109 QList<MissingData_t> rgMissingData;
110 QString fullPathOnVehicle;
118 bool inProgress()
const {
return fileSize > 0; }
126 fullPathOnVehicle.clear();
128 rgMissingData.clear();
133 struct ListDirectoryState_t {
135 uint32_t expectedOffset;
136 QString fullPathOnVehicle;
137 QStringList rgDirectoryList;
140 bool inProgress()
const {
return !fullPathOnVehicle.isEmpty(); }
145 fullPathOnVehicle.clear();
146 rgDirectoryList.clear();
151 struct DeleteFileState_t {
152 QString fullPathOnVehicle;
155 bool inProgress()
const {
return !fullPathOnVehicle.isEmpty(); }
158 fullPathOnVehicle.clear();
163 struct UploadState_t {
165 uint32_t totalBytesSent;
167 uint32_t lastChunkSize;
169 QString fullPathOnVehicle;
170 QString localFilePath;
174 bool inProgress()
const {
return file.isOpen(); }
183 fullPathOnVehicle.clear();
184 localFilePath.clear();
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);
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);
237 void _terminateSessionBegin (
void);
238 void _terminateSessionAckOrNak (
const MavlinkFTP::Request* ackOrNak);
239 void _terminateSessionTimeout (
void);
240 void _terminateComplete (
void);
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;
253 static const int _ackOrNakTimeoutMsecs = 1000;
254 static const int _maxRetry = 3;