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