8#include <QtCore/QFileInfo>
18 _ackOrNakTimeoutTimer.setSingleShot(
true);
20 _ackOrNakTimeoutTimer.setInterval(
qgcApp()->runningUnitTests() ? kTestAckTimeoutMs : _ackOrNakTimeoutMsecs);
21 connect(&_ackOrNakTimeoutTimer, &QTimer::timeout,
this, &FTPManager::_ackOrNakTimeout);
24 Q_ASSERT(
sizeof(MavlinkFTP::RequestHeader) == 12);
29bool FTPManager::download(uint8_t fromCompId,
const QString& fromURI,
const QString& toDir,
const QString& fileName,
bool checksize)
31 qCDebug(FTPManagerLog) <<
"Download fromCompId:" << fromCompId
32 <<
"fromURI:" << fromURI
34 <<
"fileName:" << fileName;
36 if (!_rgStateMachine.isEmpty()) {
37 qCDebug(FTPManagerLog) <<
"Cannot download. Already in another operation";
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 },
48 for (
size_t i=0; i<
sizeof(rgDownloadStateMachine)/
sizeof(rgDownloadStateMachine[0]); i++) {
49 _rgStateMachine.append(rgDownloadStateMachine[i]);
52 _downloadState.reset();
53 _downloadState.toDir.setPath(toDir);
54 _downloadState.checksize = checksize;
56 if (!_parseURI(fromCompId, fromURI, _downloadState.fullPathOnVehicle, _ftpCompId)) {
57 qCWarning(FTPManagerLog) <<
"_parseURI failed";
63 int lastDirSlashIndex;
64 for (lastDirSlashIndex=_downloadState.fullPathOnVehicle.size()-1; lastDirSlashIndex>=0; lastDirSlashIndex--) {
65 if (_downloadState.fullPathOnVehicle[lastDirSlashIndex] ==
'/') {
71 if (fileName.isEmpty()) {
72 _downloadState.fileName = _downloadState.fullPathOnVehicle.right(_downloadState.fullPathOnVehicle.size() - lastDirSlashIndex);
74 _downloadState.fileName = fileName;
77 qCDebug(FTPManagerLog) <<
"_downloadState.fullPathOnVehicle:_downloadState.fileName" << _downloadState.fullPathOnVehicle << _downloadState.fileName;
86 qCDebug(FTPManagerLog) <<
"upload fromFile:" << fromFile <<
"toURI:" << toURI <<
"toCompId:" << toCompId;
88 if (!_rgStateMachine.isEmpty()) {
89 qCDebug(FTPManagerLog) <<
"Cannot upload. Already in another operation";
93 QFileInfo sourceInfo(fromFile);
94 if (!sourceInfo.exists() || !sourceInfo.isFile()) {
95 qCWarning(FTPManagerLog) <<
"Cannot upload. Source file missing" << fromFile;
99 if (sourceInfo.size() > std::numeric_limits<uint32_t>::max()) {
100 qCWarning(FTPManagerLog) <<
"Cannot upload. File too large" << fromFile << sourceInfo.size();
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();
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;
120 if (!_parseURI(toCompId, toURI, _uploadState.fullPathOnVehicle, _ftpCompId)) {
121 qCWarning(FTPManagerLog) <<
"_parseURI failed";
122 _uploadState.reset();
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 },
132 for (
size_t i=0; i<
sizeof(rgUploadStateMachine)/
sizeof(rgUploadStateMachine[0]); i++) {
133 _rgStateMachine.append(rgUploadStateMachine[i]);
136 _startStateMachine();
143 qCDebug(FTPManagerLog) <<
"list directory fromURI:" << fromURI <<
"fromCompId:" << fromCompId;
145 if (!_rgStateMachine.isEmpty()) {
146 qCDebug(FTPManagerLog) <<
"Cannot list directory. Already in another operation";
150 static const StateFunctions_t rgStateMachine[] = {
151 { &FTPManager::_listDirectoryBegin, &FTPManager::_listDirectoryAckOrNak, &FTPManager::_listDirectoryTimeout },
152 { &FTPManager::_listDirectoryCompleteNoError,
nullptr,
nullptr },
154 for (
size_t i=0; i<
sizeof(rgStateMachine)/
sizeof(rgStateMachine[0]); i++) {
155 _rgStateMachine.append(rgStateMachine[i]);
158 _listDirectoryState.reset();
160 if (!_parseURI(fromCompId, fromURI, _listDirectoryState.fullPathOnVehicle, _ftpCompId)) {
161 qCWarning(FTPManagerLog) <<
"_parseURI failed";
165 qCDebug(FTPManagerLog) <<
"_listDirectoryState.fullPathOnVehicle" << _listDirectoryState.fullPathOnVehicle;
167 _startStateMachine();
174 qCDebug(FTPManagerLog) <<
"delete file fromURI:" << fromURI <<
"fromCompId:" << fromCompId;
176 if (!_rgStateMachine.isEmpty()) {
177 qCDebug(FTPManagerLog) <<
"Cannot delete file. Already in another operation";
181 static const StateFunctions_t rgStateMachine[] = {
182 { &FTPManager::_deleteFileBegin, &FTPManager::_deleteFileAckOrNak, &FTPManager::_deleteFileTimeout },
183 { &FTPManager::_deleteCompleteNoError,
nullptr,
nullptr },
185 for (
size_t i=0; i<
sizeof(rgStateMachine)/
sizeof(rgStateMachine[0]); i++) {
186 _rgStateMachine.append(rgStateMachine[i]);
189 _deleteState.reset();
191 if (!_parseURI(fromCompId, fromURI, _deleteState.fullPathOnVehicle, _ftpCompId)) {
192 qCWarning(FTPManagerLog) <<
"_parseURI failed";
193 _rgStateMachine.clear();
197 qCDebug(FTPManagerLog) <<
"_deleteState.fullPathOnVehicle" << _deleteState.fullPathOnVehicle;
199 _startStateMachine();
206 if (!_downloadState.inProgress()) {
210 _ackOrNakTimeoutTimer.stop();
211 _rgStateMachine.clear();
212 static const StateFunctions_t rgTerminateStateMachine[] = {
213 { &FTPManager::_terminateSessionBegin, &FTPManager::_terminateSessionAckOrNak, &FTPManager::_terminateSessionTimeout },
214 { &FTPManager::_terminateComplete,
nullptr,
nullptr },
216 for (
size_t i=0; i<
sizeof(rgTerminateStateMachine)/
sizeof(rgTerminateStateMachine[0]); i++) {
217 _rgStateMachine.append(rgTerminateStateMachine[i]);
219 _downloadState.retryCount = 0;
220 _startStateMachine();
225 if (!_listDirectoryState.inProgress()) {
229 if (_rgStateMachine.isEmpty()) {
233 _listDirectoryComplete(tr(
"Aborted"));
238 if (!_uploadState.inProgress()) {
242 _uploadState.cancelled =
true;
243 _ackOrNakTimeoutTimer.stop();
244 _rgStateMachine.clear();
246 if (_uploadState.sessionId != 0) {
247 static const StateFunctions_t rgTerminateStateMachine[] = {
248 { &FTPManager::_terminateUploadSessionBegin, &FTPManager::_terminateUploadSessionAckOrNak, &FTPManager::_terminateUploadSessionTimeout },
249 { &FTPManager::_uploadFinalize,
nullptr,
nullptr },
251 for (
size_t i=0; i<
sizeof(rgTerminateStateMachine)/
sizeof(rgTerminateStateMachine[0]); i++) {
252 _rgStateMachine.append(rgTerminateStateMachine[i]);
254 _uploadState.retryCount = 0;
255 _startStateMachine();
257 _uploadComplete(tr(
"Aborted"));
263 if (!_deleteState.inProgress()) {
267 _deleteComplete(tr(
"Aborted"));
270void FTPManager::_terminateSessionBegin(
void)
272 MavlinkFTP::Request request{};
273 request.hdr.session = _downloadState.sessionId;
275 _sendRequestExpectAck(&request);
278void FTPManager::_terminateSessionAckOrNak(
const MavlinkFTP::Request *ackOrNak)
282 qCDebug(FTPManagerLog) <<
"_terminateSessionAckOrNak: Ack disregarding ack for incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
285 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
286 qCDebug(FTPManagerLog) <<
"_terminateSessionAckOrNak: Ack disregarding ack for incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
290 _ackOrNakTimeoutTimer.stop();
291 _advanceStateMachine();
294void FTPManager::_terminateSessionTimeout(
void)
296 if (++_downloadState.retryCount > _maxRetry) {
297 qCDebug(FTPManagerLog) << QString(
"_terminateSessionTimeout retries exceeded");
298 _downloadComplete(tr(
"Download failed"));
301 qCDebug(FTPManagerLog) << QString(
"_terminateSessionTimeout: retrying - retryCount(%1)").arg(_downloadState.retryCount);
302 _terminateSessionBegin();
307void FTPManager::_terminateComplete(
void)
309 _downloadComplete(
"Aborted");
314void FTPManager::_downloadComplete(
const QString& errorMsg)
316 qCDebug(FTPManagerLog) << QString(
"_downloadComplete: errorMsg(%1)").arg(errorMsg);
318 QString downloadFilePath = _downloadState.toDir.absoluteFilePath(_downloadState.fileName);
319 QString
error = errorMsg;
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();
336void FTPManager::_listDirectoryComplete(
const QString& errorMsg)
338 qCDebug(FTPManagerLog) << QString(
"_listDirectoryComplete: errorMsg(%1)").arg(errorMsg);
340 _ackOrNakTimeoutTimer.stop();
341 _rgStateMachine.clear();
342 _currentStateMachineIndex = -1;
344 QStringList rgDirectoryList = _listDirectoryState.rgDirectoryList;
345 if (!errorMsg.isEmpty()) {
346 rgDirectoryList.clear();
349 _listDirectoryState.reset();
354void FTPManager::_deleteFileBegin(
void)
356 qCDebug(FTPManagerLog) <<
"file" << _deleteState.fullPathOnVehicle;
358 MavlinkFTP::Request request{};
359 request.hdr.session = 0;
361 request.hdr.offset = 0;
362 request.hdr.size = 0;
363 _fillRequestDataWithString(&request, _deleteState.fullPathOnVehicle);
364 _sendRequestExpectAck(&request);
367void FTPManager::_deleteFileAckOrNak(
const MavlinkFTP::Request* ackOrNak)
371 qCDebug(FTPManagerLog) <<
"_deleteFileAckOrNak: Ack disregarding ack for incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
374 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
375 qCDebug(FTPManagerLog) <<
"_deleteFileAckOrNak: Ack disregarding ack for incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
379 _ackOrNakTimeoutTimer.stop();
382 _advanceStateMachine();
384 qCDebug(FTPManagerLog) <<
"_deleteFileAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
385 _deleteComplete(tr(
"Delete failed") +
": " + _errorMsgFromNak(ackOrNak));
389void FTPManager::_deleteFileTimeout(
void)
391 if (++_deleteState.retryCount > _maxRetry) {
392 qCDebug(FTPManagerLog) << QString(
"_deleteFileTimeout retries exceeded");
393 _deleteComplete(tr(
"Delete failed"));
395 qCDebug(FTPManagerLog) << QString(
"_deleteFileTimeout: retrying - retryCount(%1)").arg(_deleteState.retryCount);
400void FTPManager::_deleteComplete(
const QString& errorMsg)
402 qCDebug(FTPManagerLog) << QString(
"_deleteComplete: errorMsg(%1)").arg(errorMsg);
404 const QString deletedPath = _deleteState.fullPathOnVehicle;
406 _ackOrNakTimeoutTimer.stop();
407 _rgStateMachine.clear();
408 _currentStateMachineIndex = -1;
410 _deleteState.reset();
415void FTPManager::_createFileBegin(
void)
417 qCDebug(FTPManagerLog) <<
"file" << _uploadState.fullPathOnVehicle;
419 MavlinkFTP::Request request{};
420 request.hdr.session = 0;
422 request.hdr.offset = 0;
423 request.hdr.size = 0;
424 _fillRequestDataWithString(&request, _uploadState.fullPathOnVehicle);
425 _sendRequestExpectAck(&request);
428void FTPManager::_createFileAckOrNak(
const MavlinkFTP::Request* ackOrNak)
432 qCDebug(FTPManagerLog) <<
"_createFileAckOrNak: Ack disregarding ack for incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
435 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
436 qCDebug(FTPManagerLog) <<
"_createFileAckOrNak: Ack disregarding ack for incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
440 _ackOrNakTimeoutTimer.stop();
443 qCDebug(FTPManagerLog) <<
"_createFileAckOrNak: Ack - sessionId" << ackOrNak->hdr.session;
445 _uploadState.sessionId = ackOrNak->hdr.session;
446 _advanceStateMachine();
448 qCDebug(FTPManagerLog) <<
"_createFileAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
449 _uploadComplete(tr(
"Upload failed for: %1 - error: %2").arg(_uploadState.fullPathOnVehicle).arg(_errorMsgFromNak(ackOrNak)));
453void FTPManager::_createFileTimeout(
void)
455 qCDebug(FTPManagerLog) <<
"_createFileTimeout";
456 _uploadComplete(tr(
"Upload failed for: %1 - no response from vehicle").arg(_uploadState.fullPathOnVehicle));
459void FTPManager::_writeFileBegin(
void)
461 _writeFileWorker(
true );
464void FTPManager::_writeFileWorker(
bool firstRequest)
466 if (!_uploadState.file.isOpen()) {
467 _uploadComplete(tr(
"Upload failed for: %1 - file not open").arg(_uploadState.fullPathOnVehicle));
471 if (_uploadState.totalBytesSent >= _uploadState.fileSize) {
472 _advanceStateMachine();
476 qCDebug(FTPManagerLog) <<
"_writeFileWorker: offset:firstRequest:retryCount" << _uploadState.totalBytesSent << firstRequest << _uploadState.retryCount;
478 MavlinkFTP::Request request{};
479 request.hdr.session = _uploadState.sessionId;
481 request.hdr.offset = _uploadState.totalBytesSent;
484 _uploadState.retryCount = 0;
486 _expectedIncomingSeqNumber -= 2;
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);
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));
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));
508 request.hdr.size =
static_cast<uint8_t
>(bytesRead);
509 _uploadState.lastChunkSize =
static_cast<uint32_t
>(bytesRead);
511 _sendRequestExpectAck(&request);
514void FTPManager::_writeFileAckOrNak(
const MavlinkFTP::Request* ackOrNak)
519 qCDebug(FTPManagerLog) <<
"_writeFileAckOrNak: Disregarding due to incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
522 if (ackOrNak->hdr.session != _uploadState.sessionId) {
523 qCDebug(FTPManagerLog) <<
"_writeFileAckOrNak: Disregarding due to incorrect session id actual:expected" << ackOrNak->hdr.session << _uploadState.sessionId;
527 _ackOrNakTimeoutTimer.stop();
530 if (ackOrNak->hdr.seqNumber < _expectedIncomingSeqNumber) {
531 qCDebug(FTPManagerLog) <<
"_writeFileAckOrNak: Disregarding Ack due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
535 if (ackOrNak->hdr.size != 0) {
536 qCDebug(FTPManagerLog) <<
"_writeFileAckOrNak: unexpected ack size expected:actual 0" << ackOrNak->hdr.size;
539 _uploadState.totalBytesSent += _uploadState.lastChunkSize;
540 _uploadState.lastChunkSize = 0;
541 _expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber;
543 if (_uploadState.fileSize != 0) {
544 emit
commandProgress(
static_cast<float>(_uploadState.totalBytesSent) /
static_cast<float>(_uploadState.fileSize));
547 if (_uploadState.totalBytesSent >= _uploadState.fileSize) {
548 _advanceStateMachine();
550 _writeFileWorker(
true );
553 qCDebug(FTPManagerLog) <<
"_writeFileAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
554 _uploadComplete(tr(
"Upload failed for: %1 - error: %2").arg(_uploadState.fullPathOnVehicle).arg(_errorMsgFromNak(ackOrNak)));
558void FTPManager::_writeFileTimeout(
void)
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));
564 qCDebug(FTPManagerLog) << QString(
"_writeFileTimeout: retrying - retryCount(%1) offset(%2)").arg(_uploadState.retryCount).arg(_uploadState.totalBytesSent);
565 _writeFileWorker(
false );
569void FTPManager::_terminateUploadSessionBegin(
void)
571 if (_uploadState.sessionId == 0) {
572 qCWarning(FTPManagerLog) <<
"_terminateUploadSessionBegin: No session to terminate";
573 _advanceStateMachine();
577 MavlinkFTP::Request request{};
578 request.hdr.session = _uploadState.sessionId;
580 _sendRequestExpectAck(&request);
583void FTPManager::_terminateUploadSessionAckOrNak(
const MavlinkFTP::Request* ackOrNak)
587 qCDebug(FTPManagerLog) <<
"_terminateUploadSessionAckOrNak: Ack disregarding ack for incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
590 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
591 qCDebug(FTPManagerLog) <<
"_terminateUploadSessionAckOrNak: Ack disregarding ack for incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
595 _ackOrNakTimeoutTimer.stop();
598 qCDebug(FTPManagerLog) <<
"_terminateUploadSessionAckOrNak: Ack";
599 _advanceStateMachine();
601 qCDebug(FTPManagerLog) <<
"_terminateUploadSessionAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
602 _uploadComplete(tr(
"Upload failed for: %1 - error: %2").arg(_uploadState.fullPathOnVehicle).arg(_errorMsgFromNak(ackOrNak)));
606void FTPManager::_terminateUploadSessionTimeout(
void)
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));
612 qCDebug(FTPManagerLog) << QString(
"_terminateUploadSessionTimeout: retrying - retryCount(%1)").arg(_uploadState.retryCount);
613 _terminateUploadSessionBegin();
617void FTPManager::_uploadFinalize(
void)
619 QString
error = _uploadState.cancelled ? tr(
"Aborted for: %1").arg(_uploadState.fullPathOnVehicle) : QString();
620 _uploadComplete(
error);
623void FTPManager::_uploadComplete(
const QString& errorMsg)
625 qCDebug(FTPManagerLog) << QString(
"_uploadComplete: errorMsg(%1)").arg(errorMsg)
626 <<
"local" << _uploadState.localFilePath
627 <<
"remote" << _uploadState.fullPathOnVehicle;
629 QString remotePath = _uploadState.fullPathOnVehicle;
631 _ackOrNakTimeoutTimer.stop();
632 _rgStateMachine.clear();
633 _currentStateMachineIndex = -1;
635 if (_uploadState.file.isOpen()) {
636 _uploadState.file.close();
639 _uploadState.reset();
646 if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL ||
647 message.sysid != _vehicle->
id() || message.compid != _ftpCompId) {
651 if (_currentStateMachineIndex == -1) {
655 mavlink_file_transfer_protocol_t data;
656 mavlink_msg_file_transfer_protocol_decode(&message, &data);
660 if (data.target_system != qgcId) {
664 MavlinkFTP::Request* request = (MavlinkFTP::Request*)&data.payload[0];
667 if (request->hdr.size >
sizeof(request->data)) {
668 qCWarning(FTPManagerLog) <<
"_mavlinkMessageReceived: hdr.size exceeds data array, discarding." << request->hdr.size;
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
681 qCDebug(FTPManagerLog) <<
"_mavlinkMessageReceived: hdr.opcode:hdr.req_opcode:seqNumber"
683 << request->hdr.seqNumber;
685 (this->*_rgStateMachine[_currentStateMachineIndex].ackNakFn)(request);
688void FTPManager::_startStateMachine(
void)
690 _currentStateMachineIndex = -1;
691 _advanceStateMachine();
694void FTPManager::_advanceStateMachine(
void)
696 _currentStateMachineIndex++;
697 (this->*_rgStateMachine[_currentStateMachineIndex].beginFn)();
700void FTPManager::_ackOrNakTimeout(
void)
702 (this->*_rgStateMachine[_currentStateMachineIndex].timeoutFn)();
705void FTPManager::_fillRequestDataWithString(MavlinkFTP::Request* request,
const QString& str)
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)));
711QString FTPManager::_errorMsgFromNak(
const MavlinkFTP::Request* nak)
718 errorMsg = tr(
"Invalid Nak format");
720 errorMsg = tr(
"errno %1").arg(nak->data[1]);
728void FTPManager::_openFileROBegin(
void)
730 MavlinkFTP::Request request{};
731 request.hdr.session = 0;
733 request.hdr.offset = 0;
734 request.hdr.size = 0;
735 _fillRequestDataWithString(&request, _downloadState.fullPathOnVehicle);
736 _sendRequestExpectAck(&request);
739void FTPManager::_openFileROTimeout(
void)
741 qCDebug(FTPManagerLog) <<
"_openFileROTimeout";
742 _downloadComplete(tr(
"Download failed"));
745void FTPManager::_openFileROAckOrNak(
const MavlinkFTP::Request* ackOrNak)
749 qCDebug(FTPManagerLog) <<
"_openFileROAckOrNak: Ack disregarding ack for incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
752 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
753 qCDebug(FTPManagerLog) <<
"_openFileROAckOrNak: Ack disregarding ack for incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
757 _ackOrNakTimeoutTimer.stop();
760 qCDebug(FTPManagerLog) <<
"_openFileROAckOrNak: Ack - sessionId:openFileLength" << ackOrNak->hdr.session << ackOrNak->openFileLength;
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"));
768 _downloadState.sessionId = ackOrNak->hdr.session;
769 _downloadState.fileSize = ackOrNak->openFileLength;
770 _downloadState.expectedOffset = 0;
772 _downloadState.file.setFileName(_downloadState.toDir.filePath(_downloadState.fileName));
773 if (_downloadState.file.open(QFile::WriteOnly | QFile::Truncate)) {
774 _advanceStateMachine();
776 qCDebug(FTPManagerLog) <<
"_openFileROAckOrNak: Ack _downloadState.file open failed" << _downloadState.file.errorString();
777 _downloadComplete(tr(
"Download failed"));
780 qCDebug(FTPManagerLog) <<
"_handlOpenFileROAck: Nak -" << _errorMsgFromNak(ackOrNak);
781 _downloadComplete(tr(
"Download failed") +
": " + _errorMsgFromNak(ackOrNak));
785void FTPManager::_burstReadFileWorker(
bool firstRequest)
787 qCDebug(FTPManagerLog) <<
"_burstReadFileWorker: starting burst at offset:firstRequest:retryCount" << _downloadState.expectedOffset << firstRequest << _downloadState.retryCount;
789 MavlinkFTP::Request request{};
790 request.hdr.session = _downloadState.sessionId;
792 request.hdr.offset = _downloadState.expectedOffset;
793 request.hdr.size =
sizeof(request.data);
796 _downloadState.retryCount = 0;
799 _expectedIncomingSeqNumber -= 2;
802 _sendRequestExpectAck(&request);
805void FTPManager::_burstReadFileBegin(
void)
807 _burstReadFileWorker(
true );
810void FTPManager::_burstReadFileAckOrNak(
const MavlinkFTP::Request* ackOrNak)
815 qCDebug(FTPManagerLog) <<
"_burstReadFileAckOrNak: Disregarding due to incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
818 if (ackOrNak->hdr.session != _downloadState.sessionId) {
819 qCDebug(FTPManagerLog) <<
"_burstReadFileAckOrNak: Disregarding due to incorrect session id actual:expected" << ackOrNak->hdr.session << _downloadState.sessionId;
823 _ackOrNakTimeoutTimer.stop();
826 if (ackOrNak->hdr.seqNumber < _expectedIncomingSeqNumber) {
827 qCDebug(FTPManagerLog) <<
"_burstReadFileAckOrNak: Disregarding Ack due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
831 qCDebug(FTPManagerLog) << QString(
"_burstReadFileAckOrNak: Ack offset(%1) size(%2) burstComplete(%3)").arg(ackOrNak->hdr.offset).arg(ackOrNak->hdr.size).arg(ackOrNak->hdr.burstComplete);
833 if (ackOrNak->hdr.offset != _downloadState.expectedOffset) {
834 if (ackOrNak->hdr.offset > _downloadState.expectedOffset) {
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;
843 _ackOrNakTimeoutTimer.start();
844 qCDebug(FTPManagerLog) <<
"_handleBurstReadFileAck: received offset less than expected offset received:expected" << ackOrNak->hdr.offset << _downloadState.expectedOffset;
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"));
855 _downloadState.bytesWritten += ackOrNak->hdr.size;
856 _downloadState.expectedOffset = ackOrNak->hdr.offset + ackOrNak->hdr.size;
858 if (ackOrNak->hdr.burstComplete) {
860 _expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber;
861 _burstReadFileWorker(
true );
864 _expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber + 1;
865 _ackOrNakTimeoutTimer.start();
869 if (_downloadState.fileSize != 0) {
870 emit
commandProgress((
float)(_downloadState.bytesWritten) / (
float)_downloadState.fileSize);
877 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
878 qCDebug(FTPManagerLog) <<
"_burstReadFileAckOrNak: EOF Nak"
879 "with incorrect sequence nr actual:expected"
880 << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
882 _expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber;
883 _burstReadFileWorker(
true);
885 qCDebug(FTPManagerLog) <<
"_burstReadFileAckOrNak EOF";
886 _advanceStateMachine();
889 qCDebug(FTPManagerLog) <<
"_burstReadFileAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
890 _downloadComplete(tr(
"Download failed"));
895void FTPManager::_burstReadFileTimeout(
void)
897 if (++_downloadState.retryCount > _maxRetry) {
898 qCDebug(FTPManagerLog) << QString(
"_burstReadFileTimeout retries exceeded");
899 _downloadComplete(tr(
"Download failed"));
902 qCDebug(FTPManagerLog) << QString(
"_burstReadFileTimeout: retrying - retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedOffset);
903 _burstReadFileWorker(
false );
907void FTPManager::_listDirectoryWorker(
bool firstRequest)
909 qCDebug(FTPManagerLog) <<
"_listDirectoryWorker: offset:firstRequest:retryCount" << _listDirectoryState.expectedOffset << firstRequest << _listDirectoryState.retryCount;
911 MavlinkFTP::Request request{};
912 request.hdr.session = _downloadState.sessionId;
914 request.hdr.offset = _listDirectoryState.expectedOffset;
915 request.hdr.size =
sizeof(request.data);
916 _fillRequestDataWithString(&request, _listDirectoryState.fullPathOnVehicle);
919 _listDirectoryState.retryCount = 0;
922 _expectedIncomingSeqNumber -= 2;
925 _sendRequestExpectAck(&request);
928void FTPManager::_listDirectoryBegin(
void)
930 _listDirectoryWorker(
true );
933void FTPManager::_listDirectoryAckOrNak(
const MavlinkFTP::Request* ackOrNak)
938 qCDebug(FTPManagerLog) <<
"_listDirectoryAckOrNak: Disregarding due to incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
942 _ackOrNakTimeoutTimer.stop();
945 if (ackOrNak->hdr.seqNumber < _expectedIncomingSeqNumber) {
946 qCDebug(FTPManagerLog) <<
"_listDirectoryAckOrNak: Disregarding Ack due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
950 qCDebug(FTPManagerLog) << QString(
"_listDirectoryAckOrNak: Ack size(%1)").arg(ackOrNak->hdr.size);
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++;
962 _expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber;
963 _listDirectoryWorker(
true );
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();
974 qCDebug(FTPManagerLog) <<
"_listDirectoryAckOrNak EOF";
975 _advanceStateMachine();
978 qCDebug(FTPManagerLog) <<
"_listDirectoryAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
979 _listDirectoryComplete(tr(
"List directory failed"));
984void FTPManager::_listDirectoryTimeout(
void)
986 if (++_listDirectoryState.retryCount > _maxRetry) {
987 qCDebug(FTPManagerLog) << QString(
"_listDirectoryTimeout retries exceeded");
988 _listDirectoryComplete(tr(
"List directory failed"));
991 qCDebug(FTPManagerLog) << QString(
"_listDirectoryTimeout: retrying - retryCount(%1) offset(%2)").arg(_listDirectoryState.retryCount).arg(_listDirectoryState.expectedOffset);
992 _listDirectoryWorker(
false );
996void FTPManager::_fillMissingBlocksWorker(
bool firstRequest)
998 if (_downloadState.rgMissingData.count()) {
999 MavlinkFTP::Request request{};
1000 MissingData_t& missingData = _downloadState.rgMissingData.first();
1002 uint32_t cBytesToRead = qMin((uint32_t)
sizeof(request.data), missingData.cBytesMissing);
1004 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksBegin: offset:cBytesToRead" << missingData.offset << cBytesToRead;
1006 request.hdr.session = _downloadState.sessionId;
1008 request.hdr.offset = missingData.offset;
1009 request.hdr.size = cBytesToRead;
1012 _downloadState.retryCount = 0;
1015 _expectedIncomingSeqNumber -= 2;
1017 _downloadState.expectedOffset = request.hdr.offset;
1019 _sendRequestExpectAck(&request);
1022 if (_downloadState.checksize ==
false || _downloadState.bytesWritten == _downloadState.fileSize) {
1023 _advanceStateMachine();
1025 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksWorker: no missing blocks but file still incomplete - bytesWritten:fileSize" << _downloadState.bytesWritten << _downloadState.fileSize;
1026 _downloadComplete(tr(
"Download failed"));
1031void FTPManager::_fillMissingBlocksBegin(
void)
1033 _fillMissingBlocksWorker(
true );
1036void FTPManager::_fillMissingBlocksAckOrNak(
const MavlinkFTP::Request* ackOrNak)
1041 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksAckOrNak: Disregarding due to incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
1044 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
1045 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksAckOrNak: Disregarding due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
1048 if (ackOrNak->hdr.session != _downloadState.sessionId) {
1049 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksAckOrNak: Disregarding due to incorrect session id actual:expected" << ackOrNak->hdr.session << _downloadState.sessionId;
1053 _ackOrNakTimeoutTimer.stop();
1056 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksAckOrNak: Ack offset:size" << ackOrNak->hdr.offset << ackOrNak->hdr.size;
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"));
1066 qCDebug(FTPManagerLog) << QString(
"_fillMissingBlocksAckOrNak: Ack offset mismatch retry, retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedOffset);
1067 _fillMissingBlocksWorker(
false );
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"));
1077 _downloadState.bytesWritten += ackOrNak->hdr.size;
1079 MissingData_t& missingData = _downloadState.rgMissingData.first();
1080 missingData.offset += ackOrNak->hdr.size;
1081 missingData.cBytesMissing -= ackOrNak->hdr.size;
1082 if (missingData.cBytesMissing == 0) {
1084 _downloadState.rgMissingData.takeFirst();
1088 _fillMissingBlocksWorker(
true );
1091 if (_downloadState.fileSize != 0) {
1092 emit
commandProgress((
float)(_downloadState.bytesWritten) / (
float)_downloadState.fileSize);
1098 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksAckOrNak EOF";
1099 if (_downloadState.checksize ==
false || _downloadState.bytesWritten == _downloadState.fileSize) {
1101 _advanceStateMachine();
1106 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
1107 _downloadComplete(tr(
"Download failed"));
1111void FTPManager::_fillMissingBlocksTimeout(
void)
1113 if (++_downloadState.retryCount > _maxRetry) {
1114 qCDebug(FTPManagerLog) << QString(
"_fillMissingBlocksTimeout retries exceeded");
1115 _downloadComplete(tr(
"Download failed"));
1118 qCDebug(FTPManagerLog) << QString(
"_fillMissingBlocksTimeout: retrying - retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedOffset);
1119 _fillMissingBlocksWorker(
false );
1123void FTPManager::_resetSessionsBegin(
void)
1125 MavlinkFTP::Request request{};
1127 request.hdr.size = 0;
1128 _sendRequestExpectAck(&request);
1131void FTPManager::_resetSessionsAckOrNak(
const MavlinkFTP::Request* ackOrNak)
1136 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksAckOrNak: Disregarding due to incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
1139 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
1140 qCDebug(FTPManagerLog) <<
"_resetSessionsAckOrNak: Disregarding due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
1144 _ackOrNakTimeoutTimer.stop();
1147 qCDebug(FTPManagerLog) <<
"_resetSessionsAckOrNak: Ack";
1148 _advanceStateMachine();
1150 qCDebug(FTPManagerLog) <<
"_resetSessionsAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
1151 _downloadComplete(QString());
1155void FTPManager::_resetSessionsTimeout(
void)
1157 qCDebug(FTPManagerLog) <<
"_resetSessionsTimeout";
1158 _downloadComplete(QString());
1161void FTPManager::_sendRequestExpectAck(MavlinkFTP::Request* request)
1163 _ackOrNakTimeoutTimer.start();
1167 request->hdr.seqNumber = _expectedIncomingSeqNumber + 1;
1168 _expectedIncomingSeqNumber += 2;
1175 sharedLink->mavlinkChannel(),
1183 qCDebug(FTPManagerLog) <<
"_sendRequestExpectAck No primary link. Allowing timeout to fail sequence.";
1187bool FTPManager::_parseURI(uint8_t fromCompId,
const QString& uri, QString& parsedURI, uint8_t& compId)
1190 compId = (fromCompId == MAV_COMP_ID_ALL) ? (uint8_t)MAV_COMP_ID_AUTOPILOT1 : fromCompId;
1194 if (parsedURI.startsWith(ftpPrefix, Qt::CaseInsensitive)) {
1195 parsedURI = parsedURI.right(parsedURI.length() - ftpPrefix.length() + 1);
1197 if (parsedURI.contains(
"://")) {
1198 qCWarning(FTPManagerLog) <<
"Incorrect uri scheme or format" << uri;
1203 QRegularExpression regEx(
"^/??\\[\\;comp\\=(\\d+)\\]");
1204 QRegularExpressionMatch match = regEx.match(parsedURI);
1205 if (match.hasMatch()) {
1207 compId = match.captured(1).toUInt(&ok);
1209 qCWarning(FTPManagerLog) <<
"Incorrect format for component id" << uri;
1213 qCDebug(FTPManagerLog) <<
"Found compId in MAVLink FTP URI: " << compId;
1214 parsedURI.replace(QRegularExpression(
"\\[\\;comp\\=\\d+\\]"),
"");
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
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)
static constexpr const char * mavlinkFTPScheme
void uploadComplete(const QString &file, const QString &errorMsg)
void commandProgress(float value)
void downloadComplete(const QString &file, const QString &errorMsg)
void cancelListDirectory()
void deleteComplete(const QString &file, const QString &errorMsg)
bool download(uint8_t fromCompId, const QString &fromURI, const QString &toDir, const QString &fileName="", bool checksize=true)
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].
@ kErrEOF
Offset past end of file for List and Read commands.
@ kErrFailErrno
errno sent back in PayloadHeader.data[1]
static QString errorCodeToString(ErrorCode_t errorCode)
@ kCmdRemoveFile
Remove file at <path>
@ kCmdWriteFile
Writes <size> bytes to <offset> in <session>
@ kCmdCreateFile
Creates file at <path> for writing, returns <session>
@ kCmdOpenFileRO
Opens file at <path> for reading, returns <session>
@ kCmdReadFile
Reads <size> bytes from <offset> in <session>
@ kCmdResetSessions
Terminates all open Read sessions.
@ kCmdBurstReadFile
Burst download session file.
@ kCmdTerminateSession
Terminates open Read session.
@ kCmdListDirectory
List files in <path> from <offset>
static QString opCodeToString(OpCode_t opCode)
WeakLinkInterfacePtr primaryLink() const
VehicleLinkManager * vehicleLinkManager()
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)