QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
FTPManager.cc
Go to the documentation of this file.
1#include "FTPManager.h"
2#include "MAVLinkProtocol.h"
3#include "AppMessages.h"
5#include "Vehicle.h"
7
8#include <QtCore/QFile>
9#include <QtCore/QFileInfo>
10#include <QtCore/QDir>
11#include <limits>
12
13QGC_LOGGING_CATEGORY(FTPManagerLog, "Vehicle.FTPManager")
14
16 : QObject (vehicle)
17 , _vehicle (vehicle)
18{
19 _ackOrNakTimeoutTimer.setSingleShot(true);
20 // Mock link responds immediately if at all, speed up unit tests with faster timeout
21 _ackOrNakTimeoutTimer.setInterval(QGC::runningUnitTests() ? kTestAckTimeoutMs : _ackOrNakTimeoutMsecs);
22 connect(&_ackOrNakTimeoutTimer, &QTimer::timeout, this, &FTPManager::_ackOrNakTimeout);
23
24 // Make sure we don't have bad structure packing
25 Q_ASSERT(sizeof(MavlinkFTP::RequestHeader) == 12);
26
27 _uploadState.reset();
28}
29
30bool FTPManager::download(uint8_t fromCompId, const QString& fromURI, const QString& toDir, const QString& fileName, bool checksize)
31{
32 qCDebug(FTPManagerLog) << "Download fromCompId:" << fromCompId
33 << "fromURI:" << fromURI
34 << "to:" << toDir
35 << "fileName:" << fileName;
36
37 if (!_rgStateMachine.isEmpty()) {
38 qCDebug(FTPManagerLog) << "Cannot download. Already in another operation";
39 return false;
40 }
41
42 static const StateFunctions_t rgDownloadStateMachine[] = {
43 { &FTPManager::_openFileROBegin, &FTPManager::_openFileROAckOrNak, &FTPManager::_openFileROTimeout },
44 { &FTPManager::_burstReadFileBegin, &FTPManager::_burstReadFileAckOrNak, &FTPManager::_burstReadFileTimeout },
45 { &FTPManager::_fillMissingBlocksBegin, &FTPManager::_fillMissingBlocksAckOrNak, &FTPManager::_fillMissingBlocksTimeout },
46 { &FTPManager::_resetSessionsBegin, &FTPManager::_resetSessionsAckOrNak, &FTPManager::_resetSessionsTimeout },
47 { &FTPManager::_downloadCompleteNoError, nullptr, nullptr },
48 };
49 for (size_t i=0; i<sizeof(rgDownloadStateMachine)/sizeof(rgDownloadStateMachine[0]); i++) {
50 _rgStateMachine.append(rgDownloadStateMachine[i]);
51 }
52
53 _downloadState.reset();
54 _downloadState.toDir.setPath(toDir);
55 _downloadState.checksize = checksize;
56
57 if (!_parseURI(fromCompId, fromURI, _downloadState.fullPathOnVehicle, _ftpCompId)) {
58 qCWarning(FTPManagerLog) << "_parseURI failed";
59 return false;
60 }
61
62 // We need to strip off the file name from the fully qualified path. We can't use the usual QDir
63 // routines because this path does not exist locally.
64 int lastDirSlashIndex;
65 for (lastDirSlashIndex=_downloadState.fullPathOnVehicle.size()-1; lastDirSlashIndex>=0; lastDirSlashIndex--) {
66 if (_downloadState.fullPathOnVehicle[lastDirSlashIndex] == '/') {
67 break;
68 }
69 }
70 lastDirSlashIndex++; // move past slash
71
72 if (fileName.isEmpty()) {
73 _downloadState.fileName = _downloadState.fullPathOnVehicle.right(_downloadState.fullPathOnVehicle.size() - lastDirSlashIndex);
74 } else {
75 _downloadState.fileName = fileName;
76 }
77
78 qCDebug(FTPManagerLog) << "_downloadState.fullPathOnVehicle:_downloadState.fileName" << _downloadState.fullPathOnVehicle << _downloadState.fileName;
79
80 _startStateMachine();
81
82 return true;
83}
84
85bool FTPManager::upload(uint8_t toCompId, const QString& toURI, const QString& fromFile)
86{
87 qCDebug(FTPManagerLog) << "upload fromFile:" << fromFile << "toURI:" << toURI << "toCompId:" << toCompId;
88
89 if (!_rgStateMachine.isEmpty()) {
90 qCDebug(FTPManagerLog) << "Cannot upload. Already in another operation";
91 return false;
92 }
93
94 QFileInfo sourceInfo(fromFile);
95 if (!sourceInfo.exists() || !sourceInfo.isFile()) {
96 qCWarning(FTPManagerLog) << "Cannot upload. Source file missing" << fromFile;
97 return false;
98 }
99
100 if (sourceInfo.size() > std::numeric_limits<uint32_t>::max()) {
101 qCWarning(FTPManagerLog) << "Cannot upload. File too large" << fromFile << sourceInfo.size();
102 return false;
103 }
104
105 _uploadState.reset();
106 _uploadState.localFilePath = fromFile;
107 _uploadState.file.setFileName(fromFile);
108 if (!_uploadState.file.open(QFile::ReadOnly)) {
109 qCWarning(FTPManagerLog) << "Cannot upload. Failed to open file" << fromFile << _uploadState.file.errorString();
110 _uploadState.reset();
111 return false;
112 }
113
114 _uploadState.fileSize = static_cast<uint32_t>(sourceInfo.size());
115 _uploadState.totalBytesSent = 0;
116 _uploadState.lastChunkSize = 0;
117 _uploadState.retryCount = 0;
118 _uploadState.sessionId = 0;
119 _uploadState.cancelled = false;
120
121 if (!_parseURI(toCompId, toURI, _uploadState.fullPathOnVehicle, _ftpCompId)) {
122 qCWarning(FTPManagerLog) << "_parseURI failed";
123 _uploadState.reset();
124 return false;
125 }
126
127 static const StateFunctions_t rgUploadStateMachine[] = {
128 { &FTPManager::_createFileBegin, &FTPManager::_createFileAckOrNak, &FTPManager::_createFileTimeout },
129 { &FTPManager::_writeFileBegin, &FTPManager::_writeFileAckOrNak, &FTPManager::_writeFileTimeout },
130 { &FTPManager::_resetSessionsBegin, &FTPManager::_resetSessionsAckOrNak, &FTPManager::_resetSessionsTimeout },
131 { &FTPManager::_uploadFinalize, nullptr, nullptr },
132 };
133 for (size_t i=0; i<sizeof(rgUploadStateMachine)/sizeof(rgUploadStateMachine[0]); i++) {
134 _rgStateMachine.append(rgUploadStateMachine[i]);
135 }
136
137 _startStateMachine();
138
139 return true;
140}
141
142bool FTPManager::listDirectory(uint8_t fromCompId, const QString& fromURI)
143{
144 qCDebug(FTPManagerLog) << "list directory fromURI:" << fromURI << "fromCompId:" << fromCompId;
145
146 if (!_rgStateMachine.isEmpty()) {
147 qCDebug(FTPManagerLog) << "Cannot list directory. Already in another operation";
148 return false;
149 }
150
151 static const StateFunctions_t rgStateMachine[] = {
152 { &FTPManager::_listDirectoryBegin, &FTPManager::_listDirectoryAckOrNak, &FTPManager::_listDirectoryTimeout },
153 { &FTPManager::_listDirectoryCompleteNoError, nullptr, nullptr },
154 };
155 for (size_t i=0; i<sizeof(rgStateMachine)/sizeof(rgStateMachine[0]); i++) {
156 _rgStateMachine.append(rgStateMachine[i]);
157 }
158
159 _listDirectoryState.reset();
160
161 if (!_parseURI(fromCompId, fromURI, _listDirectoryState.fullPathOnVehicle, _ftpCompId)) {
162 qCWarning(FTPManagerLog) << "_parseURI failed";
163 return false;
164 }
165
166 qCDebug(FTPManagerLog) << "_listDirectoryState.fullPathOnVehicle" << _listDirectoryState.fullPathOnVehicle;
167
168 _startStateMachine();
169
170 return true;
171}
172
173bool FTPManager::deleteFile(uint8_t fromCompId, const QString& fromURI)
174{
175 qCDebug(FTPManagerLog) << "delete file fromURI:" << fromURI << "fromCompId:" << fromCompId;
176
177 if (!_rgStateMachine.isEmpty()) {
178 qCDebug(FTPManagerLog) << "Cannot delete file. Already in another operation";
179 return false;
180 }
181
182 static const StateFunctions_t rgStateMachine[] = {
183 { &FTPManager::_deleteFileBegin, &FTPManager::_deleteFileAckOrNak, &FTPManager::_deleteFileTimeout },
184 { &FTPManager::_deleteCompleteNoError, nullptr, nullptr },
185 };
186 for (size_t i=0; i<sizeof(rgStateMachine)/sizeof(rgStateMachine[0]); i++) {
187 _rgStateMachine.append(rgStateMachine[i]);
188 }
189
190 _deleteState.reset();
191
192 if (!_parseURI(fromCompId, fromURI, _deleteState.fullPathOnVehicle, _ftpCompId)) {
193 qCWarning(FTPManagerLog) << "_parseURI failed";
194 _rgStateMachine.clear();
195 return false;
196 }
197
198 qCDebug(FTPManagerLog) << "_deleteState.fullPathOnVehicle" << _deleteState.fullPathOnVehicle;
199
200 _startStateMachine();
201
202 return true;
203}
204
206{
207 if (!_downloadState.inProgress()) {
208 return;
209 }
210
211 _ackOrNakTimeoutTimer.stop();
212 _rgStateMachine.clear();
213 static const StateFunctions_t rgTerminateStateMachine[] = {
214 { &FTPManager::_terminateSessionBegin, &FTPManager::_terminateSessionAckOrNak, &FTPManager::_terminateSessionTimeout },
215 { &FTPManager::_terminateComplete, nullptr, nullptr },
216 };
217 for (size_t i=0; i<sizeof(rgTerminateStateMachine)/sizeof(rgTerminateStateMachine[0]); i++) {
218 _rgStateMachine.append(rgTerminateStateMachine[i]);
219 }
220 _downloadState.retryCount = 0;
221 _startStateMachine();
222}
223
225{
226 if (!_listDirectoryState.inProgress()) {
227 return;
228 }
229
230 if (_rgStateMachine.isEmpty()) {
231 return;
232 }
233
234 _listDirectoryComplete(tr("Aborted"));
235}
236
238{
239 if (!_uploadState.inProgress()) {
240 return;
241 }
242
243 _uploadState.cancelled = true;
244 _ackOrNakTimeoutTimer.stop();
245 _rgStateMachine.clear();
246
247 if (_uploadState.sessionId != 0) {
248 static const StateFunctions_t rgTerminateStateMachine[] = {
249 { &FTPManager::_terminateUploadSessionBegin, &FTPManager::_terminateUploadSessionAckOrNak, &FTPManager::_terminateUploadSessionTimeout },
250 { &FTPManager::_uploadFinalize, nullptr, nullptr },
251 };
252 for (size_t i=0; i<sizeof(rgTerminateStateMachine)/sizeof(rgTerminateStateMachine[0]); i++) {
253 _rgStateMachine.append(rgTerminateStateMachine[i]);
254 }
255 _uploadState.retryCount = 0;
256 _startStateMachine();
257 } else {
258 _uploadComplete(tr("Aborted"));
259 }
260}
261
263{
264 if (!_deleteState.inProgress()) {
265 return;
266 }
267
268 _deleteComplete(tr("Aborted"));
269}
270
271void FTPManager::_terminateSessionBegin(void)
272{
273 MavlinkFTP::Request request{};
274 request.hdr.session = _downloadState.sessionId;
275 request.hdr.opcode = MavlinkFTP::kCmdTerminateSession;
276 _sendRequestExpectAck(&request);
277}
278
279void FTPManager::_terminateSessionAckOrNak(const MavlinkFTP::Request *ackOrNak)
280{
281 MavlinkFTP::OpCode_t requestOpCode = static_cast<MavlinkFTP::OpCode_t>(ackOrNak->hdr.req_opcode);
282 if (requestOpCode != MavlinkFTP::kCmdTerminateSession) {
283 qCDebug(FTPManagerLog) << "_terminateSessionAckOrNak: Ack disregarding ack for incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode);
284 return;
285 }
286 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
287 qCDebug(FTPManagerLog) << "_terminateSessionAckOrNak: Ack disregarding ack for incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
288 return;
289 }
290
291 _ackOrNakTimeoutTimer.stop();
292 _advanceStateMachine();
293}
294
295void FTPManager::_terminateSessionTimeout(void)
296{
297 if (++_downloadState.retryCount > _maxRetry) {
298 qCDebug(FTPManagerLog) << QString("_terminateSessionTimeout retries exceeded");
299 _downloadComplete(tr("Download failed"));
300 } else {
301 // Try again
302 qCDebug(FTPManagerLog) << QString("_terminateSessionTimeout: retrying - retryCount(%1)").arg(_downloadState.retryCount);
303 _terminateSessionBegin();
304 }
305
306}
307
308void FTPManager::_terminateComplete(void)
309{
310 _downloadComplete("Aborted");
311}
312
315void FTPManager::_downloadComplete(const QString& errorMsg)
316{
317 qCDebug(FTPManagerLog) << QString("_downloadComplete: errorMsg(%1)").arg(errorMsg);
318
319 QString downloadFilePath = _downloadState.toDir.absoluteFilePath(_downloadState.fileName);
320 QString error = errorMsg;
321
322 _ackOrNakTimeoutTimer.stop();
323 _rgStateMachine.clear();
324 _currentStateMachineIndex = -1;
325 if (_downloadState.file.isOpen()) {
326 _downloadState.file.close();
327 if (!errorMsg.isEmpty()) {
328 _downloadState.file.remove();
329 }
330 }
331
332 emit downloadComplete(downloadFilePath, errorMsg);
333}
334
337void FTPManager::_listDirectoryComplete(const QString& errorMsg)
338{
339 qCDebug(FTPManagerLog) << QString("_listDirectoryComplete: errorMsg(%1)").arg(errorMsg);
340
341 _ackOrNakTimeoutTimer.stop();
342 _rgStateMachine.clear();
343 _currentStateMachineIndex = -1;
344
345 QStringList rgDirectoryList = _listDirectoryState.rgDirectoryList;
346 if (!errorMsg.isEmpty()) {
347 rgDirectoryList.clear();
348 }
349
350 _listDirectoryState.reset();
351
352 emit listDirectoryComplete(errorMsg.isEmpty() ? rgDirectoryList : QStringList(), errorMsg);
353}
354
355void FTPManager::_deleteFileBegin(void)
356{
357 qCDebug(FTPManagerLog) << "file" << _deleteState.fullPathOnVehicle;
358
359 MavlinkFTP::Request request{};
360 request.hdr.session = 0;
361 request.hdr.opcode = MavlinkFTP::kCmdRemoveFile;
362 request.hdr.offset = 0;
363 request.hdr.size = 0;
364 _fillRequestDataWithString(&request, _deleteState.fullPathOnVehicle);
365 _sendRequestExpectAck(&request);
366}
367
368void FTPManager::_deleteFileAckOrNak(const MavlinkFTP::Request* ackOrNak)
369{
370 MavlinkFTP::OpCode_t requestOpCode = static_cast<MavlinkFTP::OpCode_t>(ackOrNak->hdr.req_opcode);
371 if (requestOpCode != MavlinkFTP::kCmdRemoveFile) {
372 qCDebug(FTPManagerLog) << "_deleteFileAckOrNak: Ack disregarding ack for incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode);
373 return;
374 }
375 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
376 qCDebug(FTPManagerLog) << "_deleteFileAckOrNak: Ack disregarding ack for incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
377 return;
378 }
379
380 _ackOrNakTimeoutTimer.stop();
381
382 if (ackOrNak->hdr.opcode == MavlinkFTP::kRspAck) {
383 _advanceStateMachine();
384 } else if (ackOrNak->hdr.opcode == MavlinkFTP::kRspNak) {
385 qCDebug(FTPManagerLog) << "_deleteFileAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
386 _deleteComplete(tr("Delete failed") + ": " + _errorMsgFromNak(ackOrNak));
387 }
388}
389
390void FTPManager::_deleteFileTimeout(void)
391{
392 if (++_deleteState.retryCount > _maxRetry) {
393 qCDebug(FTPManagerLog) << QString("_deleteFileTimeout retries exceeded");
394 _deleteComplete(tr("Delete failed"));
395 } else {
396 qCDebug(FTPManagerLog) << QString("_deleteFileTimeout: retrying - retryCount(%1)").arg(_deleteState.retryCount);
397 _deleteFileBegin();
398 }
399}
400
401void FTPManager::_deleteComplete(const QString& errorMsg)
402{
403 qCDebug(FTPManagerLog) << QString("_deleteComplete: errorMsg(%1)").arg(errorMsg);
404
405 const QString deletedPath = _deleteState.fullPathOnVehicle;
406
407 _ackOrNakTimeoutTimer.stop();
408 _rgStateMachine.clear();
409 _currentStateMachineIndex = -1;
410
411 _deleteState.reset();
412
413 emit deleteComplete(deletedPath, errorMsg);
414}
415
416void FTPManager::_createFileBegin(void)
417{
418 qCDebug(FTPManagerLog) << "file" << _uploadState.fullPathOnVehicle;
419
420 MavlinkFTP::Request request{};
421 request.hdr.session = 0;
422 request.hdr.opcode = MavlinkFTP::kCmdCreateFile;
423 request.hdr.offset = 0;
424 request.hdr.size = 0;
425 _fillRequestDataWithString(&request, _uploadState.fullPathOnVehicle);
426 _sendRequestExpectAck(&request);
427}
428
429void FTPManager::_createFileAckOrNak(const MavlinkFTP::Request* ackOrNak)
430{
431 MavlinkFTP::OpCode_t requestOpCode = static_cast<MavlinkFTP::OpCode_t>(ackOrNak->hdr.req_opcode);
432 if (requestOpCode != MavlinkFTP::kCmdCreateFile) {
433 qCDebug(FTPManagerLog) << "_createFileAckOrNak: Ack disregarding ack for incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode);
434 return;
435 }
436 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
437 qCDebug(FTPManagerLog) << "_createFileAckOrNak: Ack disregarding ack for incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
438 return;
439 }
440
441 _ackOrNakTimeoutTimer.stop();
442
443 if (ackOrNak->hdr.opcode == MavlinkFTP::kRspAck) {
444 qCDebug(FTPManagerLog) << "_createFileAckOrNak: Ack - sessionId" << ackOrNak->hdr.session;
445
446 _uploadState.sessionId = ackOrNak->hdr.session;
447 _advanceStateMachine();
448 } else if (ackOrNak->hdr.opcode == MavlinkFTP::kRspNak) {
449 qCDebug(FTPManagerLog) << "_createFileAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
450 _uploadComplete(tr("Upload failed for: %1 - error: %2").arg(_uploadState.fullPathOnVehicle).arg(_errorMsgFromNak(ackOrNak)));
451 }
452}
453
454void FTPManager::_createFileTimeout(void)
455{
456 qCDebug(FTPManagerLog) << "_createFileTimeout";
457 _uploadComplete(tr("Upload failed for: %1 - no response from vehicle").arg(_uploadState.fullPathOnVehicle));
458}
459
460void FTPManager::_writeFileBegin(void)
461{
462 _writeFileWorker(true /* firstRequest */);
463}
464
465void FTPManager::_writeFileWorker(bool firstRequest)
466{
467 if (!_uploadState.file.isOpen()) {
468 _uploadComplete(tr("Upload failed for: %1 - file not open").arg(_uploadState.fullPathOnVehicle));
469 return;
470 }
471
472 if (_uploadState.totalBytesSent >= _uploadState.fileSize) {
473 _advanceStateMachine();
474 return;
475 }
476
477 qCDebug(FTPManagerLog) << "_writeFileWorker: offset:firstRequest:retryCount" << _uploadState.totalBytesSent << firstRequest << _uploadState.retryCount;
478
479 MavlinkFTP::Request request{};
480 request.hdr.session = _uploadState.sessionId;
481 request.hdr.opcode = MavlinkFTP::kCmdWriteFile;
482 request.hdr.offset = _uploadState.totalBytesSent;
483
484 if (firstRequest) {
485 _uploadState.retryCount = 0;
486 } else {
487 _expectedIncomingSeqNumber -= 2;
488 }
489
490 qint64 bytesRemaining = static_cast<qint64>(_uploadState.fileSize) - static_cast<qint64>(_uploadState.totalBytesSent);
491 qint64 bytesToSend = bytesRemaining;
492 if (bytesToSend > static_cast<qint64>(sizeof(request.data))) {
493 bytesToSend = sizeof(request.data);
494 }
495
496 if (!_uploadState.file.seek(_uploadState.totalBytesSent)) {
497 qCDebug(FTPManagerLog) << "_writeFileWorker: seek failed" << _uploadState.file.errorString();
498 _uploadComplete(tr("Upload failed for: %1 - error reading file").arg(_uploadState.fullPathOnVehicle));
499 return;
500 }
501
502 qint64 bytesRead = _uploadState.file.read(reinterpret_cast<char*>(request.data), bytesToSend);
503 if (bytesRead != bytesToSend) {
504 qCDebug(FTPManagerLog) << "_writeFileWorker: read failed" << _uploadState.file.errorString();
505 _uploadComplete(tr("Upload failed for: %1 - error reading file").arg(_uploadState.fullPathOnVehicle));
506 return;
507 }
508
509 request.hdr.size = static_cast<uint8_t>(bytesRead);
510 _uploadState.lastChunkSize = static_cast<uint32_t>(bytesRead);
511
512 _sendRequestExpectAck(&request);
513}
514
515void FTPManager::_writeFileAckOrNak(const MavlinkFTP::Request* ackOrNak)
516{
517 MavlinkFTP::OpCode_t requestOpCode = static_cast<MavlinkFTP::OpCode_t>(ackOrNak->hdr.req_opcode);
518
519 if (requestOpCode != MavlinkFTP::kCmdWriteFile) {
520 qCDebug(FTPManagerLog) << "_writeFileAckOrNak: Disregarding due to incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode);
521 return;
522 }
523 if (ackOrNak->hdr.session != _uploadState.sessionId) {
524 qCDebug(FTPManagerLog) << "_writeFileAckOrNak: Disregarding due to incorrect session id actual:expected" << ackOrNak->hdr.session << _uploadState.sessionId;
525 return;
526 }
527
528 _ackOrNakTimeoutTimer.stop();
529
530 if (ackOrNak->hdr.opcode == MavlinkFTP::kRspAck) {
531 if (ackOrNak->hdr.seqNumber < _expectedIncomingSeqNumber) {
532 qCDebug(FTPManagerLog) << "_writeFileAckOrNak: Disregarding Ack due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
533 return;
534 }
535
536 if (ackOrNak->hdr.size != 0) {
537 qCDebug(FTPManagerLog) << "_writeFileAckOrNak: unexpected ack size expected:actual 0" << ackOrNak->hdr.size;
538 }
539
540 _uploadState.totalBytesSent += _uploadState.lastChunkSize;
541 _uploadState.lastChunkSize = 0;
542 _expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber;
543
544 if (_uploadState.fileSize != 0) {
545 emit commandProgress(static_cast<float>(_uploadState.totalBytesSent) / static_cast<float>(_uploadState.fileSize));
546 }
547
548 if (_uploadState.totalBytesSent >= _uploadState.fileSize) {
549 _advanceStateMachine();
550 } else {
551 _writeFileWorker(true /* firstRequest */);
552 }
553 } else if (ackOrNak->hdr.opcode == MavlinkFTP::kRspNak) {
554 qCDebug(FTPManagerLog) << "_writeFileAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
555 _uploadComplete(tr("Upload failed for: %1 - error: %2").arg(_uploadState.fullPathOnVehicle).arg(_errorMsgFromNak(ackOrNak)));
556 }
557}
558
559void FTPManager::_writeFileTimeout(void)
560{
561 if (++_uploadState.retryCount > _maxRetry) {
562 qCDebug(FTPManagerLog) << QString("_writeFileTimeout retries exceeded");
563 _uploadComplete(tr("Upload failed for: %1 - no response from vehicle").arg(_uploadState.fullPathOnVehicle));
564 } else {
565 qCDebug(FTPManagerLog) << QString("_writeFileTimeout: retrying - retryCount(%1) offset(%2)").arg(_uploadState.retryCount).arg(_uploadState.totalBytesSent);
566 _writeFileWorker(false /* firstRequest */);
567 }
568}
569
570void FTPManager::_terminateUploadSessionBegin(void)
571{
572 if (_uploadState.sessionId == 0) {
573 qCWarning(FTPManagerLog) << "_terminateUploadSessionBegin: No session to terminate";
574 _advanceStateMachine();
575 return;
576 }
577
578 MavlinkFTP::Request request{};
579 request.hdr.session = _uploadState.sessionId;
580 request.hdr.opcode = MavlinkFTP::kCmdTerminateSession;
581 _sendRequestExpectAck(&request);
582}
583
584void FTPManager::_terminateUploadSessionAckOrNak(const MavlinkFTP::Request* ackOrNak)
585{
586 MavlinkFTP::OpCode_t requestOpCode = static_cast<MavlinkFTP::OpCode_t>(ackOrNak->hdr.req_opcode);
587 if (requestOpCode != MavlinkFTP::kCmdTerminateSession) {
588 qCDebug(FTPManagerLog) << "_terminateUploadSessionAckOrNak: Ack disregarding ack for incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode);
589 return;
590 }
591 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
592 qCDebug(FTPManagerLog) << "_terminateUploadSessionAckOrNak: Ack disregarding ack for incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
593 return;
594 }
595
596 _ackOrNakTimeoutTimer.stop();
597
598 if (ackOrNak->hdr.opcode == MavlinkFTP::kRspAck) {
599 qCDebug(FTPManagerLog) << "_terminateUploadSessionAckOrNak: Ack";
600 _advanceStateMachine();
601 } else if (ackOrNak->hdr.opcode == MavlinkFTP::kRspNak) {
602 qCDebug(FTPManagerLog) << "_terminateUploadSessionAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
603 _uploadComplete(tr("Upload failed for: %1 - error: %2").arg(_uploadState.fullPathOnVehicle).arg(_errorMsgFromNak(ackOrNak)));
604 }
605}
606
607void FTPManager::_terminateUploadSessionTimeout(void)
608{
609 if (++_uploadState.retryCount > _maxRetry) {
610 qCDebug(FTPManagerLog) << QString("_terminateUploadSessionTimeout retries exceeded");
611 _uploadComplete(tr("Upload failed for: %1 - no response from vehicle").arg(_uploadState.fullPathOnVehicle));
612 } else {
613 qCDebug(FTPManagerLog) << QString("_terminateUploadSessionTimeout: retrying - retryCount(%1)").arg(_uploadState.retryCount);
614 _terminateUploadSessionBegin();
615 }
616}
617
618void FTPManager::_uploadFinalize(void)
619{
620 QString error = _uploadState.cancelled ? tr("Aborted for: %1").arg(_uploadState.fullPathOnVehicle) : QString();
621 _uploadComplete(error);
622}
623
624void FTPManager::_uploadComplete(const QString& errorMsg)
625{
626 qCDebug(FTPManagerLog) << QString("_uploadComplete: errorMsg(%1)").arg(errorMsg)
627 << "local" << _uploadState.localFilePath
628 << "remote" << _uploadState.fullPathOnVehicle;
629
630 QString remotePath = _uploadState.fullPathOnVehicle;
631
632 _ackOrNakTimeoutTimer.stop();
633 _rgStateMachine.clear();
634 _currentStateMachineIndex = -1;
635
636 if (_uploadState.file.isOpen()) {
637 _uploadState.file.close();
638 }
639
640 _uploadState.reset();
641
642 emit uploadComplete(remotePath, errorMsg);
643}
644
645void FTPManager::_mavlinkMessageReceived(const mavlink_message_t& message)
646{
647 if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL ||
648 message.sysid != _vehicle->id() || message.compid != _ftpCompId) {
649 return;
650 }
651
652 if (_currentStateMachineIndex == -1) {
653 return;
654 }
655
656 mavlink_file_transfer_protocol_t data;
657 mavlink_msg_file_transfer_protocol_decode(&message, &data);
658
659 // Make sure we are the target system
660 int qgcId = MAVLinkProtocol::instance()->getSystemId();
661 if (data.target_system != qgcId) {
662 return;
663 }
664
665 MavlinkFTP::Request* request = (MavlinkFTP::Request*)&data.payload[0];
666
667 // Reject messages where hdr.size exceeds data array bounds to prevent over-reads
668 if (request->hdr.size > sizeof(request->data)) {
669 qCWarning(FTPManagerLog) << "_mavlinkMessageReceived: hdr.size exceeds data array, discarding." << request->hdr.size;
670 return;
671 }
672
673 // Ignore old/reordered packets (handle wrap-around properly)
674 uint16_t actualIncomingSeqNumber = request->hdr.seqNumber;
675 if ((uint16_t)((_expectedIncomingSeqNumber - 1) - actualIncomingSeqNumber) < (std::numeric_limits<uint16_t>::max()/2)) {
676 qCDebug(FTPManagerLog) << "_mavlinkMessageReceived: Received old packet seqNum expected:actual" << _expectedIncomingSeqNumber << actualIncomingSeqNumber
677 << "hdr.opcode:hdr.req_opcode" << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.opcode)) << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.req_opcode));
678
679 return;
680 }
681
682 qCDebug(FTPManagerLog) << "_mavlinkMessageReceived: hdr.opcode:hdr.req_opcode:seqNumber"
683 << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.opcode)) << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.req_opcode))
684 << request->hdr.seqNumber;
685
686 (this->*_rgStateMachine[_currentStateMachineIndex].ackNakFn)(request);
687}
688
689void FTPManager::_startStateMachine(void)
690{
691 _currentStateMachineIndex = -1;
692 _advanceStateMachine();
693}
694
695void FTPManager::_advanceStateMachine(void)
696{
697 _currentStateMachineIndex++;
698 (this->*_rgStateMachine[_currentStateMachineIndex].beginFn)();
699}
700
701void FTPManager::_ackOrNakTimeout(void)
702{
703 (this->*_rgStateMachine[_currentStateMachineIndex].timeoutFn)();
704}
705
706void FTPManager::_fillRequestDataWithString(MavlinkFTP::Request* request, const QString& str)
707{
708 strncpy((char *)&request->data[0], str.toStdString().c_str(), sizeof(request->data));
709 request->hdr.size = static_cast<uint8_t>(strnlen((const char *)&request->data[0], sizeof(request->data)));
710}
711
712QString FTPManager::_errorMsgFromNak(const MavlinkFTP::Request* nak)
713{
714 QString errorMsg;
715 MavlinkFTP::ErrorCode_t errorCode = static_cast<MavlinkFTP::ErrorCode_t>(nak->data[0]);
716
717 // Nak's normally have 1 byte of data for error code, except for MavlinkFTP::kErrFailErrno which has additional byte for errno
718 if ((errorCode == MavlinkFTP::kErrFailErrno && nak->hdr.size != 2) || ((errorCode != MavlinkFTP::kErrFailErrno) && nak->hdr.size != 1)) {
719 errorMsg = tr("Invalid Nak format");
720 } else if (errorCode == MavlinkFTP::kErrFailErrno) {
721 errorMsg = tr("errno %1").arg(nak->data[1]);
722 } else {
723 errorMsg = MavlinkFTP::errorCodeToString(errorCode);
724 }
725
726 return errorMsg;
727}
728
729void FTPManager::_openFileROBegin(void)
730{
731 MavlinkFTP::Request request{};
732 request.hdr.session = 0;
733 request.hdr.opcode = MavlinkFTP::kCmdOpenFileRO;
734 request.hdr.offset = 0;
735 request.hdr.size = 0;
736 _fillRequestDataWithString(&request, _downloadState.fullPathOnVehicle);
737 _sendRequestExpectAck(&request);
738}
739
740void FTPManager::_openFileROTimeout(void)
741{
742 qCDebug(FTPManagerLog) << "_openFileROTimeout";
743 _downloadComplete(tr("Download failed"));
744}
745
746void FTPManager::_openFileROAckOrNak(const MavlinkFTP::Request* ackOrNak)
747{
748 MavlinkFTP::OpCode_t requestOpCode = static_cast<MavlinkFTP::OpCode_t>(ackOrNak->hdr.req_opcode);
749 if (requestOpCode != MavlinkFTP::kCmdOpenFileRO) {
750 qCDebug(FTPManagerLog) << "_openFileROAckOrNak: Ack disregarding ack for incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode);
751 return;
752 }
753 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
754 qCDebug(FTPManagerLog) << "_openFileROAckOrNak: Ack disregarding ack for incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
755 return;
756 }
757
758 _ackOrNakTimeoutTimer.stop();
759
760 if (ackOrNak->hdr.opcode == MavlinkFTP::kRspAck) {
761 qCDebug(FTPManagerLog) << "_openFileROAckOrNak: Ack - sessionId:openFileLength" << ackOrNak->hdr.session << ackOrNak->openFileLength;
762
763 if (ackOrNak->hdr.size != sizeof(uint32_t)) {
764 qCDebug(FTPManagerLog) << "_openFileROAckOrNak: Ack ack->hdr.size != sizeof(uint32_t)" << ackOrNak->hdr.size << sizeof(uint32_t);
765 _downloadComplete(tr("Download failed"));
766 return;
767 }
768
769 _downloadState.sessionId = ackOrNak->hdr.session;
770 _downloadState.fileSize = ackOrNak->openFileLength;
771 _downloadState.expectedOffset = 0;
772
773 _downloadState.file.setFileName(_downloadState.toDir.filePath(_downloadState.fileName));
774 if (_downloadState.file.open(QFile::WriteOnly | QFile::Truncate)) {
775 _advanceStateMachine();
776 } else {
777 qCDebug(FTPManagerLog) << "_openFileROAckOrNak: Ack _downloadState.file open failed" << _downloadState.file.errorString();
778 _downloadComplete(tr("Download failed"));
779 }
780 } else if (ackOrNak->hdr.opcode == MavlinkFTP::kRspNak) {
781 qCDebug(FTPManagerLog) << "_handlOpenFileROAck: Nak -" << _errorMsgFromNak(ackOrNak);
782 _downloadComplete(tr("Download failed") + ": " + _errorMsgFromNak(ackOrNak));
783 }
784}
785
786void FTPManager::_burstReadFileWorker(bool firstRequest)
787{
788 qCDebug(FTPManagerLog) << "_burstReadFileWorker: starting burst at offset:firstRequest:retryCount" << _downloadState.expectedOffset << firstRequest << _downloadState.retryCount;
789
790 MavlinkFTP::Request request{};
791 request.hdr.session = _downloadState.sessionId;
792 request.hdr.opcode = MavlinkFTP::kCmdBurstReadFile;
793 request.hdr.offset = _downloadState.expectedOffset;
794 request.hdr.size = sizeof(request.data);
795
796 if (firstRequest) {
797 _downloadState.retryCount = 0;
798 } else {
799 // Must used same sequence number as previous request
800 _expectedIncomingSeqNumber -= 2;
801 }
802
803 _sendRequestExpectAck(&request);
804}
805
806void FTPManager::_burstReadFileBegin(void)
807{
808 _burstReadFileWorker(true /* firstRequestr */);
809}
810
811void FTPManager::_burstReadFileAckOrNak(const MavlinkFTP::Request* ackOrNak)
812{
813 MavlinkFTP::OpCode_t requestOpCode = static_cast<MavlinkFTP::OpCode_t>(ackOrNak->hdr.req_opcode);
814
815 if (requestOpCode != MavlinkFTP::kCmdBurstReadFile) {
816 qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak: Disregarding due to incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode);
817 return;
818 }
819 if (ackOrNak->hdr.session != _downloadState.sessionId) {
820 qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak: Disregarding due to incorrect session id actual:expected" << ackOrNak->hdr.session << _downloadState.sessionId;
821 return;
822 }
823
824 _ackOrNakTimeoutTimer.stop();
825
826 if (ackOrNak->hdr.opcode == MavlinkFTP::kRspAck) {
827 if (ackOrNak->hdr.seqNumber < _expectedIncomingSeqNumber) {
828 qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak: Disregarding Ack due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
829 return;
830 }
831
832 qCDebug(FTPManagerLog) << QString("_burstReadFileAckOrNak: Ack offset(%1) size(%2) burstComplete(%3)").arg(ackOrNak->hdr.offset).arg(ackOrNak->hdr.size).arg(ackOrNak->hdr.burstComplete);
833
834 if (ackOrNak->hdr.offset != _downloadState.expectedOffset) {
835 if (ackOrNak->hdr.offset > _downloadState.expectedOffset) {
836 // There is a hole in our data, record it as missing and continue on
837 MissingData_t missingData;
838 missingData.offset = _downloadState.expectedOffset;
839 missingData.cBytesMissing = ackOrNak->hdr.offset - _downloadState.expectedOffset;
840 _downloadState.rgMissingData.append(missingData);
841 qCDebug(FTPManagerLog) << "_handleBurstReadFileAck: adding missing data offset:cBytesMissing" << missingData.offset << missingData.cBytesMissing;
842 } else {
843 // Offset is past what we have already seen, disregard and wait for something usefule
844 _ackOrNakTimeoutTimer.start();
845 qCDebug(FTPManagerLog) << "_handleBurstReadFileAck: received offset less than expected offset received:expected" << ackOrNak->hdr.offset << _downloadState.expectedOffset;
846 return;
847 }
848 }
849
850 _downloadState.file.seek(ackOrNak->hdr.offset);
851 int bytesWritten = _downloadState.file.write((const char*)ackOrNak->data, ackOrNak->hdr.size);
852 if (bytesWritten != ackOrNak->hdr.size) {
853 _downloadComplete(tr("Download failed: Error saving file"));
854 return;
855 }
856 _downloadState.bytesWritten += ackOrNak->hdr.size;
857 _downloadState.expectedOffset = ackOrNak->hdr.offset + ackOrNak->hdr.size;
858
859 if (ackOrNak->hdr.burstComplete) {
860 // The current burst is done, request next one in offset sequence
861 _expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber;
862 _burstReadFileWorker(true /* firstRequest */);
863 } else {
864 // Still within a burst, next ack should come automatically
865 _expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber + 1;
866 _ackOrNakTimeoutTimer.start();
867 }
868
869 // Emit progress last, as cancel could be called in there
870 if (_downloadState.fileSize != 0) {
871 emit commandProgress((float)(_downloadState.bytesWritten) / (float)_downloadState.fileSize);
872 }
873 } else if (ackOrNak->hdr.opcode == MavlinkFTP::kRspNak) {
874 MavlinkFTP::ErrorCode_t errorCode = static_cast<MavlinkFTP::ErrorCode_t>(ackOrNak->data[0]);
875
876 if (errorCode == MavlinkFTP::kErrEOF) {
877 // Burst sequence has gone through the whole file
878 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
879 qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak: EOF Nak"
880 "with incorrect sequence nr actual:expected"
881 << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
882 /* We have received the EOF Nak but out of sequence, i.e. data is missing */
883 _expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber;
884 _burstReadFileWorker(true); /* Retry from last expected offset */
885 } else {
886 qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak EOF";
887 _advanceStateMachine();
888 }
889 } else { /* Don't care is this is out of sequence */
890 qCDebug(FTPManagerLog) << "_burstReadFileAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
891 _downloadComplete(tr("Download failed"));
892 }
893 }
894}
895
896void FTPManager::_burstReadFileTimeout(void)
897{
898 if (++_downloadState.retryCount > _maxRetry) {
899 qCDebug(FTPManagerLog) << QString("_burstReadFileTimeout retries exceeded");
900 _downloadComplete(tr("Download failed"));
901 } else {
902 // Try again
903 qCDebug(FTPManagerLog) << QString("_burstReadFileTimeout: retrying - retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedOffset);
904 _burstReadFileWorker(false /* firstReqeust */);
905 }
906}
907
908void FTPManager::_listDirectoryWorker(bool firstRequest)
909{
910 qCDebug(FTPManagerLog) << "_listDirectoryWorker: offset:firstRequest:retryCount" << _listDirectoryState.expectedOffset << firstRequest << _listDirectoryState.retryCount;
911
912 MavlinkFTP::Request request{};
913 request.hdr.session = _downloadState.sessionId;
914 request.hdr.opcode = MavlinkFTP::kCmdListDirectory;
915 request.hdr.offset = _listDirectoryState.expectedOffset;
916 request.hdr.size = sizeof(request.data);
917 _fillRequestDataWithString(&request, _listDirectoryState.fullPathOnVehicle);
918
919 if (firstRequest) {
920 _listDirectoryState.retryCount = 0;
921 } else {
922 // Must used same sequence number as previous request
923 _expectedIncomingSeqNumber -= 2;
924 }
925
926 _sendRequestExpectAck(&request);
927}
928
929void FTPManager::_listDirectoryBegin(void)
930{
931 _listDirectoryWorker(true /* firstRequest */);
932}
933
934void FTPManager::_listDirectoryAckOrNak(const MavlinkFTP::Request* ackOrNak)
935{
936 MavlinkFTP::OpCode_t requestOpCode = static_cast<MavlinkFTP::OpCode_t>(ackOrNak->hdr.req_opcode);
937
938 if (requestOpCode != MavlinkFTP::kCmdListDirectory) {
939 qCDebug(FTPManagerLog) << "_listDirectoryAckOrNak: Disregarding due to incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode);
940 return;
941 }
942
943 _ackOrNakTimeoutTimer.stop();
944
945 if (ackOrNak->hdr.opcode == MavlinkFTP::kRspAck) {
946 if (ackOrNak->hdr.seqNumber < _expectedIncomingSeqNumber) {
947 qCDebug(FTPManagerLog) << "_listDirectoryAckOrNak: Disregarding Ack due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
948 return;
949 }
950
951 qCDebug(FTPManagerLog) << QString("_listDirectoryAckOrNak: Ack size(%1)").arg(ackOrNak->hdr.size);
952
953 // Parse entries in ackOrNak->data into _listDirectoryState.rgDirectoryList
954 const char* curDataPtr = (const char*)ackOrNak->data;
955 while (curDataPtr < (const char*)ackOrNak->data + ackOrNak->hdr.size) {
956 QString dirEntry = curDataPtr;
957 curDataPtr += dirEntry.size() + 1;
958 _listDirectoryState.rgDirectoryList.append(dirEntry);
959 _listDirectoryState.expectedOffset++;
960 }
961
962 // Request next set of directory entries
963 _expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber;
964 _listDirectoryWorker(true /* firstRequest */);
965 } else if (ackOrNak->hdr.opcode == MavlinkFTP::kRspNak) {
966 MavlinkFTP::ErrorCode_t errorCode = static_cast<MavlinkFTP::ErrorCode_t>(ackOrNak->data[0]);
967
968 if (errorCode == MavlinkFTP::kErrEOF) {
969 // All entries returned
970 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
971 qCDebug(FTPManagerLog) << "_listDirectoryAckOrNak: Disregarding Nak due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
972 _ackOrNakTimeoutTimer.start();
973 return;
974 } else {
975 qCDebug(FTPManagerLog) << "_listDirectoryAckOrNak EOF";
976 _advanceStateMachine();
977 }
978 } else { /* Don't care is this is out of sequence */
979 qCDebug(FTPManagerLog) << "_listDirectoryAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
980 _listDirectoryComplete(tr("List directory failed"));
981 }
982 }
983}
984
985void FTPManager::_listDirectoryTimeout(void)
986{
987 if (++_listDirectoryState.retryCount > _maxRetry) {
988 qCDebug(FTPManagerLog) << QString("_listDirectoryTimeout retries exceeded");
989 _listDirectoryComplete(tr("List directory failed"));
990 } else {
991 // Try again
992 qCDebug(FTPManagerLog) << QString("_listDirectoryTimeout: retrying - retryCount(%1) offset(%2)").arg(_listDirectoryState.retryCount).arg(_listDirectoryState.expectedOffset);
993 _listDirectoryWorker(false /* firstReqeust */);
994 }
995}
996
997void FTPManager::_fillMissingBlocksWorker(bool firstRequest)
998{
999 if (_downloadState.rgMissingData.count()) {
1000 MavlinkFTP::Request request{};
1001 MissingData_t& missingData = _downloadState.rgMissingData.first();
1002
1003 uint32_t cBytesToRead = qMin((uint32_t)sizeof(request.data), missingData.cBytesMissing);
1004
1005 qCDebug(FTPManagerLog) << "_fillMissingBlocksBegin: offset:cBytesToRead" << missingData.offset << cBytesToRead;
1006
1007 request.hdr.session = _downloadState.sessionId;
1008 request.hdr.opcode = MavlinkFTP::kCmdReadFile;
1009 request.hdr.offset = missingData.offset;
1010 request.hdr.size = cBytesToRead;
1011
1012 if (firstRequest) {
1013 _downloadState.retryCount = 0;
1014 } else {
1015 // Must used same sequence number as previous request
1016 _expectedIncomingSeqNumber -= 2;
1017 }
1018 _downloadState.expectedOffset = request.hdr.offset;
1019
1020 _sendRequestExpectAck(&request);
1021 } else {
1022 // We should have the full file now
1023 if (_downloadState.checksize == false || _downloadState.bytesWritten == _downloadState.fileSize) {
1024 _advanceStateMachine();
1025 } else {
1026 qCDebug(FTPManagerLog) << "_fillMissingBlocksWorker: no missing blocks but file still incomplete - bytesWritten:fileSize" << _downloadState.bytesWritten << _downloadState.fileSize;
1027 _downloadComplete(tr("Download failed"));
1028 }
1029 }
1030}
1031
1032void FTPManager::_fillMissingBlocksBegin(void)
1033{
1034 _fillMissingBlocksWorker(true /* firstRequest */);
1035}
1036
1037void FTPManager::_fillMissingBlocksAckOrNak(const MavlinkFTP::Request* ackOrNak)
1038{
1039 MavlinkFTP::OpCode_t requestOpCode = static_cast<MavlinkFTP::OpCode_t>(ackOrNak->hdr.req_opcode);
1040
1041 if (requestOpCode != MavlinkFTP::kCmdReadFile) {
1042 qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Disregarding due to incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode);
1043 return;
1044 }
1045 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
1046 qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Disregarding due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
1047 return;
1048 }
1049 if (ackOrNak->hdr.session != _downloadState.sessionId) {
1050 qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Disregarding due to incorrect session id actual:expected" << ackOrNak->hdr.session << _downloadState.sessionId;
1051 return;
1052 }
1053
1054 _ackOrNakTimeoutTimer.stop();
1055
1056 if (ackOrNak->hdr.opcode == MavlinkFTP::kRspAck) {
1057 qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Ack offset:size" << ackOrNak->hdr.offset << ackOrNak->hdr.size;
1058
1059 if (ackOrNak->hdr.offset != _downloadState.expectedOffset) {
1060 if (++_downloadState.retryCount > _maxRetry) {
1061 qCDebug(FTPManagerLog) << QString("_fillMissingBlocksAckOrNak: offset mismatch, retries exceeded");
1062 _downloadComplete(tr("Download failed"));
1063 return;
1064 }
1065
1066 // Ask for current offset again
1067 qCDebug(FTPManagerLog) << QString("_fillMissingBlocksAckOrNak: Ack offset mismatch retry, retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedOffset);
1068 _fillMissingBlocksWorker(false /* firstReqeust */);
1069 return;
1070 }
1071
1072 _downloadState.file.seek(ackOrNak->hdr.offset);
1073 int bytesWritten = _downloadState.file.write((const char*)ackOrNak->data, ackOrNak->hdr.size);
1074 if (bytesWritten != ackOrNak->hdr.size) {
1075 _downloadComplete(tr("Download failed: Error saving file"));
1076 return;
1077 }
1078 _downloadState.bytesWritten += ackOrNak->hdr.size;
1079
1080 MissingData_t& missingData = _downloadState.rgMissingData.first();
1081 missingData.offset += ackOrNak->hdr.size;
1082 missingData.cBytesMissing -= ackOrNak->hdr.size;
1083 if (missingData.cBytesMissing == 0) {
1084 // This block is finished, remove it
1085 _downloadState.rgMissingData.takeFirst();
1086 }
1087
1088 // Move on to fill in possible next hole
1089 _fillMissingBlocksWorker(true /* firstReqeust */);
1090
1091 // Emit progress last, as cancel could be called in there
1092 if (_downloadState.fileSize != 0) {
1093 emit commandProgress((float)(_downloadState.bytesWritten) / (float)_downloadState.fileSize);
1094 }
1095 } else if (ackOrNak->hdr.opcode == MavlinkFTP::kRspNak) {
1096 MavlinkFTP::ErrorCode_t errorCode = static_cast<MavlinkFTP::ErrorCode_t>(ackOrNak->data[0]);
1097
1098 if (errorCode == MavlinkFTP::kErrEOF) {
1099 qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak EOF";
1100 if (_downloadState.checksize == false || _downloadState.bytesWritten == _downloadState.fileSize) {
1101 // We've successfully complete filling in all missing blocks
1102 _advanceStateMachine();
1103 return;
1104 }
1105 }
1106
1107 qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
1108 _downloadComplete(tr("Download failed"));
1109 }
1110}
1111
1112void FTPManager::_fillMissingBlocksTimeout(void)
1113{
1114 if (++_downloadState.retryCount > _maxRetry) {
1115 qCDebug(FTPManagerLog) << QString("_fillMissingBlocksTimeout retries exceeded");
1116 _downloadComplete(tr("Download failed"));
1117 } else {
1118 // Ask for current offset again
1119 qCDebug(FTPManagerLog) << QString("_fillMissingBlocksTimeout: retrying - retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedOffset);
1120 _fillMissingBlocksWorker(false /* firstReqeust */);
1121 }
1122}
1123
1124void FTPManager::_resetSessionsBegin(void)
1125{
1126 MavlinkFTP::Request request{};
1127 request.hdr.opcode = MavlinkFTP::kCmdResetSessions;
1128 request.hdr.size = 0;
1129 _sendRequestExpectAck(&request);
1130}
1131
1132void FTPManager::_resetSessionsAckOrNak(const MavlinkFTP::Request* ackOrNak)
1133{
1134 MavlinkFTP::OpCode_t requestOpCode = static_cast<MavlinkFTP::OpCode_t>(ackOrNak->hdr.req_opcode);
1135
1136 if (requestOpCode != MavlinkFTP::kCmdResetSessions) {
1137 qCDebug(FTPManagerLog) << "_fillMissingBlocksAckOrNak: Disregarding due to incorrect requestOpCode" << MavlinkFTP::opCodeToString(requestOpCode);
1138 return;
1139 }
1140 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
1141 qCDebug(FTPManagerLog) << "_resetSessionsAckOrNak: Disregarding due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
1142 return;
1143 }
1144
1145 _ackOrNakTimeoutTimer.stop();
1146
1147 if (ackOrNak->hdr.opcode == MavlinkFTP::kRspAck) {
1148 qCDebug(FTPManagerLog) << "_resetSessionsAckOrNak: Ack";
1149 _advanceStateMachine();
1150 } else if (ackOrNak->hdr.opcode == MavlinkFTP::kRspNak) {
1151 qCDebug(FTPManagerLog) << "_resetSessionsAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
1152 _downloadComplete(QString());
1153 }
1154}
1155
1156void FTPManager::_resetSessionsTimeout(void)
1157{
1158 qCDebug(FTPManagerLog) << "_resetSessionsTimeout";
1159 _downloadComplete(QString());
1160}
1161
1162void FTPManager::_sendRequestExpectAck(MavlinkFTP::Request* request)
1163{
1164 _ackOrNakTimeoutTimer.start();
1165
1166 SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
1167 if (sharedLink) {
1168 request->hdr.seqNumber = _expectedIncomingSeqNumber + 1; // Outgoing is 1 past last incoming
1169 _expectedIncomingSeqNumber += 2;
1170
1171 qCDebug(FTPManagerLog) << "_sendRequestExpectAck opcode:" << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.opcode)) << "seqNumber:" << request->hdr.seqNumber;
1172
1173 mavlink_message_t message;
1174 mavlink_msg_file_transfer_protocol_pack_chan(MAVLinkProtocol::instance()->getSystemId(),
1176 sharedLink->mavlinkChannel(),
1177 &message,
1178 0, // Target network, 0=broadcast?
1179 _vehicle->id(),
1180 _ftpCompId,
1181 (uint8_t*)request); // Payload
1182 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), message);
1183 } else {
1184 qCDebug(FTPManagerLog) << "_sendRequestExpectAck No primary link. Allowing timeout to fail sequence.";
1185 }
1186}
1187
1188bool FTPManager::_parseURI(uint8_t fromCompId, const QString& uri, QString& parsedURI, uint8_t& compId)
1189{
1190 parsedURI = uri;
1191 compId = (fromCompId == MAV_COMP_ID_ALL) ? (uint8_t)MAV_COMP_ID_AUTOPILOT1 : fromCompId;
1192
1193 // Pull scheme off the front if there
1194 QString ftpPrefix(QStringLiteral("%1://").arg(mavlinkFTPScheme));
1195 if (parsedURI.startsWith(ftpPrefix, Qt::CaseInsensitive)) {
1196 parsedURI = parsedURI.right(parsedURI.length() - ftpPrefix.length() + 1);
1197 }
1198 if (parsedURI.contains("://")) {
1199 qCWarning(FTPManagerLog) << "Incorrect uri scheme or format" << uri;
1200 return false;
1201 }
1202
1203 // Pull component id off the front if there
1204 QRegularExpression regEx("^/??\\[\\;comp\\=(\\d+)\\]");
1205 QRegularExpressionMatch match = regEx.match(parsedURI);
1206 if (match.hasMatch()) {
1207 bool ok;
1208 compId = match.captured(1).toUInt(&ok);
1209 if (!ok) {
1210 qCWarning(FTPManagerLog) << "Incorrect format for component id" << uri;
1211 return false;
1212 }
1213
1214 qCDebug(FTPManagerLog) << "Found compId in MAVLink FTP URI: " << compId;
1215 parsedURI.replace(QRegularExpression("\\[\\;comp\\=\\d+\\]"), "");
1216 }
1217
1218 return true;
1219}
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
Error error
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
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()
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)
static int getComponentId()
static MAVLinkProtocol * instance()
int getSystemId() const
ErrorCode_t
Error codes returned in Nak response PayloadHeader.data[0].
Definition MAVLinkFTP.h:61
@ kErrEOF
Offset past end of file for List and Read commands.
Definition MAVLinkFTP.h:68
@ kErrFailErrno
errno sent back in PayloadHeader.data[1]
Definition MAVLinkFTP.h:64
static QString errorCodeToString(ErrorCode_t errorCode)
Definition MAVLinkFTP.cc:47
@ kCmdRemoveFile
Remove file at <path>
Definition MAVLinkFTP.h:47
@ kCmdWriteFile
Writes <size> bytes to <offset> in <session>
Definition MAVLinkFTP.h:46
@ kCmdCreateFile
Creates file at <path> for writing, returns <session>
Definition MAVLinkFTP.h:45
@ kCmdOpenFileRO
Opens file at <path> for reading, returns <session>
Definition MAVLinkFTP.h:43
@ kCmdReadFile
Reads <size> bytes from <offset> in <session>
Definition MAVLinkFTP.h:44
@ kCmdResetSessions
Terminates all open Read sessions.
Definition MAVLinkFTP.h:41
@ kRspAck
Ack response.
Definition MAVLinkFTP.h:56
@ kCmdBurstReadFile
Burst download session file.
Definition MAVLinkFTP.h:54
@ kCmdTerminateSession
Terminates open Read session.
Definition MAVLinkFTP.h:40
@ kRspNak
Nak response.
Definition MAVLinkFTP.h:57
@ kCmdListDirectory
List files in <path> from <offset>
Definition MAVLinkFTP.h:42
static QString opCodeToString(OpCode_t opCode)
Definition MAVLinkFTP.cc:3
WeakLinkInterfacePtr primaryLink() const
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:575
int id() const
Definition Vehicle.h:425
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1389
bool runningUnitTests()