9#include <QtCore/QFileInfo>
19 _ackOrNakTimeoutTimer.setSingleShot(
true);
21 _ackOrNakTimeoutTimer.setInterval(
QGC::runningUnitTests() ? kTestAckTimeoutMs : _ackOrNakTimeoutMsecs);
22 connect(&_ackOrNakTimeoutTimer, &QTimer::timeout,
this, &FTPManager::_ackOrNakTimeout);
25 Q_ASSERT(
sizeof(MavlinkFTP::RequestHeader) == 12);
30bool FTPManager::download(uint8_t fromCompId,
const QString& fromURI,
const QString& toDir,
const QString& fileName,
bool checksize)
32 qCDebug(FTPManagerLog) <<
"Download fromCompId:" << fromCompId
33 <<
"fromURI:" << fromURI
35 <<
"fileName:" << fileName;
37 if (!_rgStateMachine.isEmpty()) {
38 qCDebug(FTPManagerLog) <<
"Cannot download. Already in another operation";
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 },
49 for (
size_t i=0; i<
sizeof(rgDownloadStateMachine)/
sizeof(rgDownloadStateMachine[0]); i++) {
50 _rgStateMachine.append(rgDownloadStateMachine[i]);
53 _downloadState.reset();
54 _downloadState.toDir.setPath(toDir);
55 _downloadState.checksize = checksize;
57 if (!_parseURI(fromCompId, fromURI, _downloadState.fullPathOnVehicle, _ftpCompId)) {
58 qCWarning(FTPManagerLog) <<
"_parseURI failed";
64 int lastDirSlashIndex;
65 for (lastDirSlashIndex=_downloadState.fullPathOnVehicle.size()-1; lastDirSlashIndex>=0; lastDirSlashIndex--) {
66 if (_downloadState.fullPathOnVehicle[lastDirSlashIndex] ==
'/') {
72 if (fileName.isEmpty()) {
73 _downloadState.fileName = _downloadState.fullPathOnVehicle.right(_downloadState.fullPathOnVehicle.size() - lastDirSlashIndex);
75 _downloadState.fileName = fileName;
78 qCDebug(FTPManagerLog) <<
"_downloadState.fullPathOnVehicle:_downloadState.fileName" << _downloadState.fullPathOnVehicle << _downloadState.fileName;
87 qCDebug(FTPManagerLog) <<
"upload fromFile:" << fromFile <<
"toURI:" << toURI <<
"toCompId:" << toCompId;
89 if (!_rgStateMachine.isEmpty()) {
90 qCDebug(FTPManagerLog) <<
"Cannot upload. Already in another operation";
94 QFileInfo sourceInfo(fromFile);
95 if (!sourceInfo.exists() || !sourceInfo.isFile()) {
96 qCWarning(FTPManagerLog) <<
"Cannot upload. Source file missing" << fromFile;
100 if (sourceInfo.size() > std::numeric_limits<uint32_t>::max()) {
101 qCWarning(FTPManagerLog) <<
"Cannot upload. File too large" << fromFile << sourceInfo.size();
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();
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;
121 if (!_parseURI(toCompId, toURI, _uploadState.fullPathOnVehicle, _ftpCompId)) {
122 qCWarning(FTPManagerLog) <<
"_parseURI failed";
123 _uploadState.reset();
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 },
133 for (
size_t i=0; i<
sizeof(rgUploadStateMachine)/
sizeof(rgUploadStateMachine[0]); i++) {
134 _rgStateMachine.append(rgUploadStateMachine[i]);
137 _startStateMachine();
144 qCDebug(FTPManagerLog) <<
"list directory fromURI:" << fromURI <<
"fromCompId:" << fromCompId;
146 if (!_rgStateMachine.isEmpty()) {
147 qCDebug(FTPManagerLog) <<
"Cannot list directory. Already in another operation";
151 static const StateFunctions_t rgStateMachine[] = {
152 { &FTPManager::_listDirectoryBegin, &FTPManager::_listDirectoryAckOrNak, &FTPManager::_listDirectoryTimeout },
153 { &FTPManager::_listDirectoryCompleteNoError,
nullptr,
nullptr },
155 for (
size_t i=0; i<
sizeof(rgStateMachine)/
sizeof(rgStateMachine[0]); i++) {
156 _rgStateMachine.append(rgStateMachine[i]);
159 _listDirectoryState.reset();
161 if (!_parseURI(fromCompId, fromURI, _listDirectoryState.fullPathOnVehicle, _ftpCompId)) {
162 qCWarning(FTPManagerLog) <<
"_parseURI failed";
166 qCDebug(FTPManagerLog) <<
"_listDirectoryState.fullPathOnVehicle" << _listDirectoryState.fullPathOnVehicle;
168 _startStateMachine();
175 qCDebug(FTPManagerLog) <<
"delete file fromURI:" << fromURI <<
"fromCompId:" << fromCompId;
177 if (!_rgStateMachine.isEmpty()) {
178 qCDebug(FTPManagerLog) <<
"Cannot delete file. Already in another operation";
182 static const StateFunctions_t rgStateMachine[] = {
183 { &FTPManager::_deleteFileBegin, &FTPManager::_deleteFileAckOrNak, &FTPManager::_deleteFileTimeout },
184 { &FTPManager::_deleteCompleteNoError,
nullptr,
nullptr },
186 for (
size_t i=0; i<
sizeof(rgStateMachine)/
sizeof(rgStateMachine[0]); i++) {
187 _rgStateMachine.append(rgStateMachine[i]);
190 _deleteState.reset();
192 if (!_parseURI(fromCompId, fromURI, _deleteState.fullPathOnVehicle, _ftpCompId)) {
193 qCWarning(FTPManagerLog) <<
"_parseURI failed";
194 _rgStateMachine.clear();
198 qCDebug(FTPManagerLog) <<
"_deleteState.fullPathOnVehicle" << _deleteState.fullPathOnVehicle;
200 _startStateMachine();
207 if (!_downloadState.inProgress()) {
211 _ackOrNakTimeoutTimer.stop();
212 _rgStateMachine.clear();
213 static const StateFunctions_t rgTerminateStateMachine[] = {
214 { &FTPManager::_terminateSessionBegin, &FTPManager::_terminateSessionAckOrNak, &FTPManager::_terminateSessionTimeout },
215 { &FTPManager::_terminateComplete,
nullptr,
nullptr },
217 for (
size_t i=0; i<
sizeof(rgTerminateStateMachine)/
sizeof(rgTerminateStateMachine[0]); i++) {
218 _rgStateMachine.append(rgTerminateStateMachine[i]);
220 _downloadState.retryCount = 0;
221 _startStateMachine();
226 if (!_listDirectoryState.inProgress()) {
230 if (_rgStateMachine.isEmpty()) {
234 _listDirectoryComplete(tr(
"Aborted"));
239 if (!_uploadState.inProgress()) {
243 _uploadState.cancelled =
true;
244 _ackOrNakTimeoutTimer.stop();
245 _rgStateMachine.clear();
247 if (_uploadState.sessionId != 0) {
248 static const StateFunctions_t rgTerminateStateMachine[] = {
249 { &FTPManager::_terminateUploadSessionBegin, &FTPManager::_terminateUploadSessionAckOrNak, &FTPManager::_terminateUploadSessionTimeout },
250 { &FTPManager::_uploadFinalize,
nullptr,
nullptr },
252 for (
size_t i=0; i<
sizeof(rgTerminateStateMachine)/
sizeof(rgTerminateStateMachine[0]); i++) {
253 _rgStateMachine.append(rgTerminateStateMachine[i]);
255 _uploadState.retryCount = 0;
256 _startStateMachine();
258 _uploadComplete(tr(
"Aborted"));
264 if (!_deleteState.inProgress()) {
268 _deleteComplete(tr(
"Aborted"));
271void FTPManager::_terminateSessionBegin(
void)
273 MavlinkFTP::Request request{};
274 request.hdr.session = _downloadState.sessionId;
276 _sendRequestExpectAck(&request);
279void FTPManager::_terminateSessionAckOrNak(
const MavlinkFTP::Request *ackOrNak)
283 qCDebug(FTPManagerLog) <<
"_terminateSessionAckOrNak: Ack disregarding ack for incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
286 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
287 qCDebug(FTPManagerLog) <<
"_terminateSessionAckOrNak: Ack disregarding ack for incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
291 _ackOrNakTimeoutTimer.stop();
292 _advanceStateMachine();
295void FTPManager::_terminateSessionTimeout(
void)
297 if (++_downloadState.retryCount > _maxRetry) {
298 qCDebug(FTPManagerLog) << QString(
"_terminateSessionTimeout retries exceeded");
299 _downloadComplete(tr(
"Download failed"));
302 qCDebug(FTPManagerLog) << QString(
"_terminateSessionTimeout: retrying - retryCount(%1)").arg(_downloadState.retryCount);
303 _terminateSessionBegin();
308void FTPManager::_terminateComplete(
void)
310 _downloadComplete(
"Aborted");
315void FTPManager::_downloadComplete(
const QString& errorMsg)
317 qCDebug(FTPManagerLog) << QString(
"_downloadComplete: errorMsg(%1)").arg(errorMsg);
319 QString downloadFilePath = _downloadState.toDir.absoluteFilePath(_downloadState.fileName);
320 QString
error = errorMsg;
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();
337void FTPManager::_listDirectoryComplete(
const QString& errorMsg)
339 qCDebug(FTPManagerLog) << QString(
"_listDirectoryComplete: errorMsg(%1)").arg(errorMsg);
341 _ackOrNakTimeoutTimer.stop();
342 _rgStateMachine.clear();
343 _currentStateMachineIndex = -1;
345 QStringList rgDirectoryList = _listDirectoryState.rgDirectoryList;
346 if (!errorMsg.isEmpty()) {
347 rgDirectoryList.clear();
350 _listDirectoryState.reset();
355void FTPManager::_deleteFileBegin(
void)
357 qCDebug(FTPManagerLog) <<
"file" << _deleteState.fullPathOnVehicle;
359 MavlinkFTP::Request request{};
360 request.hdr.session = 0;
362 request.hdr.offset = 0;
363 request.hdr.size = 0;
364 _fillRequestDataWithString(&request, _deleteState.fullPathOnVehicle);
365 _sendRequestExpectAck(&request);
368void FTPManager::_deleteFileAckOrNak(
const MavlinkFTP::Request* ackOrNak)
372 qCDebug(FTPManagerLog) <<
"_deleteFileAckOrNak: Ack disregarding ack for incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
375 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
376 qCDebug(FTPManagerLog) <<
"_deleteFileAckOrNak: Ack disregarding ack for incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
380 _ackOrNakTimeoutTimer.stop();
383 _advanceStateMachine();
385 qCDebug(FTPManagerLog) <<
"_deleteFileAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
386 _deleteComplete(tr(
"Delete failed") +
": " + _errorMsgFromNak(ackOrNak));
390void FTPManager::_deleteFileTimeout(
void)
392 if (++_deleteState.retryCount > _maxRetry) {
393 qCDebug(FTPManagerLog) << QString(
"_deleteFileTimeout retries exceeded");
394 _deleteComplete(tr(
"Delete failed"));
396 qCDebug(FTPManagerLog) << QString(
"_deleteFileTimeout: retrying - retryCount(%1)").arg(_deleteState.retryCount);
401void FTPManager::_deleteComplete(
const QString& errorMsg)
403 qCDebug(FTPManagerLog) << QString(
"_deleteComplete: errorMsg(%1)").arg(errorMsg);
405 const QString deletedPath = _deleteState.fullPathOnVehicle;
407 _ackOrNakTimeoutTimer.stop();
408 _rgStateMachine.clear();
409 _currentStateMachineIndex = -1;
411 _deleteState.reset();
416void FTPManager::_createFileBegin(
void)
418 qCDebug(FTPManagerLog) <<
"file" << _uploadState.fullPathOnVehicle;
420 MavlinkFTP::Request request{};
421 request.hdr.session = 0;
423 request.hdr.offset = 0;
424 request.hdr.size = 0;
425 _fillRequestDataWithString(&request, _uploadState.fullPathOnVehicle);
426 _sendRequestExpectAck(&request);
429void FTPManager::_createFileAckOrNak(
const MavlinkFTP::Request* ackOrNak)
433 qCDebug(FTPManagerLog) <<
"_createFileAckOrNak: Ack disregarding ack for incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
436 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
437 qCDebug(FTPManagerLog) <<
"_createFileAckOrNak: Ack disregarding ack for incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
441 _ackOrNakTimeoutTimer.stop();
444 qCDebug(FTPManagerLog) <<
"_createFileAckOrNak: Ack - sessionId" << ackOrNak->hdr.session;
446 _uploadState.sessionId = ackOrNak->hdr.session;
447 _advanceStateMachine();
449 qCDebug(FTPManagerLog) <<
"_createFileAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
450 _uploadComplete(tr(
"Upload failed for: %1 - error: %2").arg(_uploadState.fullPathOnVehicle).arg(_errorMsgFromNak(ackOrNak)));
454void FTPManager::_createFileTimeout(
void)
456 qCDebug(FTPManagerLog) <<
"_createFileTimeout";
457 _uploadComplete(tr(
"Upload failed for: %1 - no response from vehicle").arg(_uploadState.fullPathOnVehicle));
460void FTPManager::_writeFileBegin(
void)
462 _writeFileWorker(
true );
465void FTPManager::_writeFileWorker(
bool firstRequest)
467 if (!_uploadState.file.isOpen()) {
468 _uploadComplete(tr(
"Upload failed for: %1 - file not open").arg(_uploadState.fullPathOnVehicle));
472 if (_uploadState.totalBytesSent >= _uploadState.fileSize) {
473 _advanceStateMachine();
477 qCDebug(FTPManagerLog) <<
"_writeFileWorker: offset:firstRequest:retryCount" << _uploadState.totalBytesSent << firstRequest << _uploadState.retryCount;
479 MavlinkFTP::Request request{};
480 request.hdr.session = _uploadState.sessionId;
482 request.hdr.offset = _uploadState.totalBytesSent;
485 _uploadState.retryCount = 0;
487 _expectedIncomingSeqNumber -= 2;
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);
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));
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));
509 request.hdr.size =
static_cast<uint8_t
>(bytesRead);
510 _uploadState.lastChunkSize =
static_cast<uint32_t
>(bytesRead);
512 _sendRequestExpectAck(&request);
515void FTPManager::_writeFileAckOrNak(
const MavlinkFTP::Request* ackOrNak)
520 qCDebug(FTPManagerLog) <<
"_writeFileAckOrNak: Disregarding due to incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
523 if (ackOrNak->hdr.session != _uploadState.sessionId) {
524 qCDebug(FTPManagerLog) <<
"_writeFileAckOrNak: Disregarding due to incorrect session id actual:expected" << ackOrNak->hdr.session << _uploadState.sessionId;
528 _ackOrNakTimeoutTimer.stop();
531 if (ackOrNak->hdr.seqNumber < _expectedIncomingSeqNumber) {
532 qCDebug(FTPManagerLog) <<
"_writeFileAckOrNak: Disregarding Ack due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
536 if (ackOrNak->hdr.size != 0) {
537 qCDebug(FTPManagerLog) <<
"_writeFileAckOrNak: unexpected ack size expected:actual 0" << ackOrNak->hdr.size;
540 _uploadState.totalBytesSent += _uploadState.lastChunkSize;
541 _uploadState.lastChunkSize = 0;
542 _expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber;
544 if (_uploadState.fileSize != 0) {
545 emit
commandProgress(
static_cast<float>(_uploadState.totalBytesSent) /
static_cast<float>(_uploadState.fileSize));
548 if (_uploadState.totalBytesSent >= _uploadState.fileSize) {
549 _advanceStateMachine();
551 _writeFileWorker(
true );
554 qCDebug(FTPManagerLog) <<
"_writeFileAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
555 _uploadComplete(tr(
"Upload failed for: %1 - error: %2").arg(_uploadState.fullPathOnVehicle).arg(_errorMsgFromNak(ackOrNak)));
559void FTPManager::_writeFileTimeout(
void)
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));
565 qCDebug(FTPManagerLog) << QString(
"_writeFileTimeout: retrying - retryCount(%1) offset(%2)").arg(_uploadState.retryCount).arg(_uploadState.totalBytesSent);
566 _writeFileWorker(
false );
570void FTPManager::_terminateUploadSessionBegin(
void)
572 if (_uploadState.sessionId == 0) {
573 qCWarning(FTPManagerLog) <<
"_terminateUploadSessionBegin: No session to terminate";
574 _advanceStateMachine();
578 MavlinkFTP::Request request{};
579 request.hdr.session = _uploadState.sessionId;
581 _sendRequestExpectAck(&request);
584void FTPManager::_terminateUploadSessionAckOrNak(
const MavlinkFTP::Request* ackOrNak)
588 qCDebug(FTPManagerLog) <<
"_terminateUploadSessionAckOrNak: Ack disregarding ack for incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
591 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
592 qCDebug(FTPManagerLog) <<
"_terminateUploadSessionAckOrNak: Ack disregarding ack for incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
596 _ackOrNakTimeoutTimer.stop();
599 qCDebug(FTPManagerLog) <<
"_terminateUploadSessionAckOrNak: Ack";
600 _advanceStateMachine();
602 qCDebug(FTPManagerLog) <<
"_terminateUploadSessionAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
603 _uploadComplete(tr(
"Upload failed for: %1 - error: %2").arg(_uploadState.fullPathOnVehicle).arg(_errorMsgFromNak(ackOrNak)));
607void FTPManager::_terminateUploadSessionTimeout(
void)
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));
613 qCDebug(FTPManagerLog) << QString(
"_terminateUploadSessionTimeout: retrying - retryCount(%1)").arg(_uploadState.retryCount);
614 _terminateUploadSessionBegin();
618void FTPManager::_uploadFinalize(
void)
620 QString
error = _uploadState.cancelled ? tr(
"Aborted for: %1").arg(_uploadState.fullPathOnVehicle) : QString();
621 _uploadComplete(
error);
624void FTPManager::_uploadComplete(
const QString& errorMsg)
626 qCDebug(FTPManagerLog) << QString(
"_uploadComplete: errorMsg(%1)").arg(errorMsg)
627 <<
"local" << _uploadState.localFilePath
628 <<
"remote" << _uploadState.fullPathOnVehicle;
630 QString remotePath = _uploadState.fullPathOnVehicle;
632 _ackOrNakTimeoutTimer.stop();
633 _rgStateMachine.clear();
634 _currentStateMachineIndex = -1;
636 if (_uploadState.file.isOpen()) {
637 _uploadState.file.close();
640 _uploadState.reset();
647 if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL ||
648 message.sysid != _vehicle->
id() || message.compid != _ftpCompId) {
652 if (_currentStateMachineIndex == -1) {
656 mavlink_file_transfer_protocol_t data;
657 mavlink_msg_file_transfer_protocol_decode(&message, &data);
661 if (data.target_system != qgcId) {
665 MavlinkFTP::Request* request = (MavlinkFTP::Request*)&data.payload[0];
668 if (request->hdr.size >
sizeof(request->data)) {
669 qCWarning(FTPManagerLog) <<
"_mavlinkMessageReceived: hdr.size exceeds data array, discarding." << request->hdr.size;
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
682 qCDebug(FTPManagerLog) <<
"_mavlinkMessageReceived: hdr.opcode:hdr.req_opcode:seqNumber"
684 << request->hdr.seqNumber;
686 (this->*_rgStateMachine[_currentStateMachineIndex].ackNakFn)(request);
689void FTPManager::_startStateMachine(
void)
691 _currentStateMachineIndex = -1;
692 _advanceStateMachine();
695void FTPManager::_advanceStateMachine(
void)
697 _currentStateMachineIndex++;
698 (this->*_rgStateMachine[_currentStateMachineIndex].beginFn)();
701void FTPManager::_ackOrNakTimeout(
void)
703 (this->*_rgStateMachine[_currentStateMachineIndex].timeoutFn)();
706void FTPManager::_fillRequestDataWithString(MavlinkFTP::Request* request,
const QString& str)
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)));
712QString FTPManager::_errorMsgFromNak(
const MavlinkFTP::Request* nak)
719 errorMsg = tr(
"Invalid Nak format");
721 errorMsg = tr(
"errno %1").arg(nak->data[1]);
729void FTPManager::_openFileROBegin(
void)
731 MavlinkFTP::Request request{};
732 request.hdr.session = 0;
734 request.hdr.offset = 0;
735 request.hdr.size = 0;
736 _fillRequestDataWithString(&request, _downloadState.fullPathOnVehicle);
737 _sendRequestExpectAck(&request);
740void FTPManager::_openFileROTimeout(
void)
742 qCDebug(FTPManagerLog) <<
"_openFileROTimeout";
743 _downloadComplete(tr(
"Download failed"));
746void FTPManager::_openFileROAckOrNak(
const MavlinkFTP::Request* ackOrNak)
750 qCDebug(FTPManagerLog) <<
"_openFileROAckOrNak: Ack disregarding ack for incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
753 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
754 qCDebug(FTPManagerLog) <<
"_openFileROAckOrNak: Ack disregarding ack for incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
758 _ackOrNakTimeoutTimer.stop();
761 qCDebug(FTPManagerLog) <<
"_openFileROAckOrNak: Ack - sessionId:openFileLength" << ackOrNak->hdr.session << ackOrNak->openFileLength;
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"));
769 _downloadState.sessionId = ackOrNak->hdr.session;
770 _downloadState.fileSize = ackOrNak->openFileLength;
771 _downloadState.expectedOffset = 0;
773 _downloadState.file.setFileName(_downloadState.toDir.filePath(_downloadState.fileName));
774 if (_downloadState.file.open(QFile::WriteOnly | QFile::Truncate)) {
775 _advanceStateMachine();
777 qCDebug(FTPManagerLog) <<
"_openFileROAckOrNak: Ack _downloadState.file open failed" << _downloadState.file.errorString();
778 _downloadComplete(tr(
"Download failed"));
781 qCDebug(FTPManagerLog) <<
"_handlOpenFileROAck: Nak -" << _errorMsgFromNak(ackOrNak);
782 _downloadComplete(tr(
"Download failed") +
": " + _errorMsgFromNak(ackOrNak));
786void FTPManager::_burstReadFileWorker(
bool firstRequest)
788 qCDebug(FTPManagerLog) <<
"_burstReadFileWorker: starting burst at offset:firstRequest:retryCount" << _downloadState.expectedOffset << firstRequest << _downloadState.retryCount;
790 MavlinkFTP::Request request{};
791 request.hdr.session = _downloadState.sessionId;
793 request.hdr.offset = _downloadState.expectedOffset;
794 request.hdr.size =
sizeof(request.data);
797 _downloadState.retryCount = 0;
800 _expectedIncomingSeqNumber -= 2;
803 _sendRequestExpectAck(&request);
806void FTPManager::_burstReadFileBegin(
void)
808 _burstReadFileWorker(
true );
811void FTPManager::_burstReadFileAckOrNak(
const MavlinkFTP::Request* ackOrNak)
816 qCDebug(FTPManagerLog) <<
"_burstReadFileAckOrNak: Disregarding due to incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
819 if (ackOrNak->hdr.session != _downloadState.sessionId) {
820 qCDebug(FTPManagerLog) <<
"_burstReadFileAckOrNak: Disregarding due to incorrect session id actual:expected" << ackOrNak->hdr.session << _downloadState.sessionId;
824 _ackOrNakTimeoutTimer.stop();
827 if (ackOrNak->hdr.seqNumber < _expectedIncomingSeqNumber) {
828 qCDebug(FTPManagerLog) <<
"_burstReadFileAckOrNak: Disregarding Ack due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
832 qCDebug(FTPManagerLog) << QString(
"_burstReadFileAckOrNak: Ack offset(%1) size(%2) burstComplete(%3)").arg(ackOrNak->hdr.offset).arg(ackOrNak->hdr.size).arg(ackOrNak->hdr.burstComplete);
834 if (ackOrNak->hdr.offset != _downloadState.expectedOffset) {
835 if (ackOrNak->hdr.offset > _downloadState.expectedOffset) {
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;
844 _ackOrNakTimeoutTimer.start();
845 qCDebug(FTPManagerLog) <<
"_handleBurstReadFileAck: received offset less than expected offset received:expected" << ackOrNak->hdr.offset << _downloadState.expectedOffset;
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"));
856 _downloadState.bytesWritten += ackOrNak->hdr.size;
857 _downloadState.expectedOffset = ackOrNak->hdr.offset + ackOrNak->hdr.size;
859 if (ackOrNak->hdr.burstComplete) {
861 _expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber;
862 _burstReadFileWorker(
true );
865 _expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber + 1;
866 _ackOrNakTimeoutTimer.start();
870 if (_downloadState.fileSize != 0) {
871 emit
commandProgress((
float)(_downloadState.bytesWritten) / (
float)_downloadState.fileSize);
878 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
879 qCDebug(FTPManagerLog) <<
"_burstReadFileAckOrNak: EOF Nak"
880 "with incorrect sequence nr actual:expected"
881 << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
883 _expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber;
884 _burstReadFileWorker(
true);
886 qCDebug(FTPManagerLog) <<
"_burstReadFileAckOrNak EOF";
887 _advanceStateMachine();
890 qCDebug(FTPManagerLog) <<
"_burstReadFileAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
891 _downloadComplete(tr(
"Download failed"));
896void FTPManager::_burstReadFileTimeout(
void)
898 if (++_downloadState.retryCount > _maxRetry) {
899 qCDebug(FTPManagerLog) << QString(
"_burstReadFileTimeout retries exceeded");
900 _downloadComplete(tr(
"Download failed"));
903 qCDebug(FTPManagerLog) << QString(
"_burstReadFileTimeout: retrying - retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedOffset);
904 _burstReadFileWorker(
false );
908void FTPManager::_listDirectoryWorker(
bool firstRequest)
910 qCDebug(FTPManagerLog) <<
"_listDirectoryWorker: offset:firstRequest:retryCount" << _listDirectoryState.expectedOffset << firstRequest << _listDirectoryState.retryCount;
912 MavlinkFTP::Request request{};
913 request.hdr.session = _downloadState.sessionId;
915 request.hdr.offset = _listDirectoryState.expectedOffset;
916 request.hdr.size =
sizeof(request.data);
917 _fillRequestDataWithString(&request, _listDirectoryState.fullPathOnVehicle);
920 _listDirectoryState.retryCount = 0;
923 _expectedIncomingSeqNumber -= 2;
926 _sendRequestExpectAck(&request);
929void FTPManager::_listDirectoryBegin(
void)
931 _listDirectoryWorker(
true );
934void FTPManager::_listDirectoryAckOrNak(
const MavlinkFTP::Request* ackOrNak)
939 qCDebug(FTPManagerLog) <<
"_listDirectoryAckOrNak: Disregarding due to incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
943 _ackOrNakTimeoutTimer.stop();
946 if (ackOrNak->hdr.seqNumber < _expectedIncomingSeqNumber) {
947 qCDebug(FTPManagerLog) <<
"_listDirectoryAckOrNak: Disregarding Ack due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
951 qCDebug(FTPManagerLog) << QString(
"_listDirectoryAckOrNak: Ack size(%1)").arg(ackOrNak->hdr.size);
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++;
963 _expectedIncomingSeqNumber = ackOrNak->hdr.seqNumber;
964 _listDirectoryWorker(
true );
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();
975 qCDebug(FTPManagerLog) <<
"_listDirectoryAckOrNak EOF";
976 _advanceStateMachine();
979 qCDebug(FTPManagerLog) <<
"_listDirectoryAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
980 _listDirectoryComplete(tr(
"List directory failed"));
985void FTPManager::_listDirectoryTimeout(
void)
987 if (++_listDirectoryState.retryCount > _maxRetry) {
988 qCDebug(FTPManagerLog) << QString(
"_listDirectoryTimeout retries exceeded");
989 _listDirectoryComplete(tr(
"List directory failed"));
992 qCDebug(FTPManagerLog) << QString(
"_listDirectoryTimeout: retrying - retryCount(%1) offset(%2)").arg(_listDirectoryState.retryCount).arg(_listDirectoryState.expectedOffset);
993 _listDirectoryWorker(
false );
997void FTPManager::_fillMissingBlocksWorker(
bool firstRequest)
999 if (_downloadState.rgMissingData.count()) {
1000 MavlinkFTP::Request request{};
1001 MissingData_t& missingData = _downloadState.rgMissingData.first();
1003 uint32_t cBytesToRead = qMin((uint32_t)
sizeof(request.data), missingData.cBytesMissing);
1005 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksBegin: offset:cBytesToRead" << missingData.offset << cBytesToRead;
1007 request.hdr.session = _downloadState.sessionId;
1009 request.hdr.offset = missingData.offset;
1010 request.hdr.size = cBytesToRead;
1013 _downloadState.retryCount = 0;
1016 _expectedIncomingSeqNumber -= 2;
1018 _downloadState.expectedOffset = request.hdr.offset;
1020 _sendRequestExpectAck(&request);
1023 if (_downloadState.checksize ==
false || _downloadState.bytesWritten == _downloadState.fileSize) {
1024 _advanceStateMachine();
1026 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksWorker: no missing blocks but file still incomplete - bytesWritten:fileSize" << _downloadState.bytesWritten << _downloadState.fileSize;
1027 _downloadComplete(tr(
"Download failed"));
1032void FTPManager::_fillMissingBlocksBegin(
void)
1034 _fillMissingBlocksWorker(
true );
1037void FTPManager::_fillMissingBlocksAckOrNak(
const MavlinkFTP::Request* ackOrNak)
1042 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksAckOrNak: Disregarding due to incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
1045 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
1046 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksAckOrNak: Disregarding due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
1049 if (ackOrNak->hdr.session != _downloadState.sessionId) {
1050 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksAckOrNak: Disregarding due to incorrect session id actual:expected" << ackOrNak->hdr.session << _downloadState.sessionId;
1054 _ackOrNakTimeoutTimer.stop();
1057 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksAckOrNak: Ack offset:size" << ackOrNak->hdr.offset << ackOrNak->hdr.size;
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"));
1067 qCDebug(FTPManagerLog) << QString(
"_fillMissingBlocksAckOrNak: Ack offset mismatch retry, retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedOffset);
1068 _fillMissingBlocksWorker(
false );
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"));
1078 _downloadState.bytesWritten += ackOrNak->hdr.size;
1080 MissingData_t& missingData = _downloadState.rgMissingData.first();
1081 missingData.offset += ackOrNak->hdr.size;
1082 missingData.cBytesMissing -= ackOrNak->hdr.size;
1083 if (missingData.cBytesMissing == 0) {
1085 _downloadState.rgMissingData.takeFirst();
1089 _fillMissingBlocksWorker(
true );
1092 if (_downloadState.fileSize != 0) {
1093 emit
commandProgress((
float)(_downloadState.bytesWritten) / (
float)_downloadState.fileSize);
1099 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksAckOrNak EOF";
1100 if (_downloadState.checksize ==
false || _downloadState.bytesWritten == _downloadState.fileSize) {
1102 _advanceStateMachine();
1107 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
1108 _downloadComplete(tr(
"Download failed"));
1112void FTPManager::_fillMissingBlocksTimeout(
void)
1114 if (++_downloadState.retryCount > _maxRetry) {
1115 qCDebug(FTPManagerLog) << QString(
"_fillMissingBlocksTimeout retries exceeded");
1116 _downloadComplete(tr(
"Download failed"));
1119 qCDebug(FTPManagerLog) << QString(
"_fillMissingBlocksTimeout: retrying - retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedOffset);
1120 _fillMissingBlocksWorker(
false );
1124void FTPManager::_resetSessionsBegin(
void)
1126 MavlinkFTP::Request request{};
1128 request.hdr.size = 0;
1129 _sendRequestExpectAck(&request);
1132void FTPManager::_resetSessionsAckOrNak(
const MavlinkFTP::Request* ackOrNak)
1137 qCDebug(FTPManagerLog) <<
"_fillMissingBlocksAckOrNak: Disregarding due to incorrect requestOpCode" <<
MavlinkFTP::opCodeToString(requestOpCode);
1140 if (ackOrNak->hdr.seqNumber != _expectedIncomingSeqNumber) {
1141 qCDebug(FTPManagerLog) <<
"_resetSessionsAckOrNak: Disregarding due to incorrect sequence actual:expected" << ackOrNak->hdr.seqNumber << _expectedIncomingSeqNumber;
1145 _ackOrNakTimeoutTimer.stop();
1148 qCDebug(FTPManagerLog) <<
"_resetSessionsAckOrNak: Ack";
1149 _advanceStateMachine();
1151 qCDebug(FTPManagerLog) <<
"_resetSessionsAckOrNak: Nak -" << _errorMsgFromNak(ackOrNak);
1152 _downloadComplete(QString());
1156void FTPManager::_resetSessionsTimeout(
void)
1158 qCDebug(FTPManagerLog) <<
"_resetSessionsTimeout";
1159 _downloadComplete(QString());
1162void FTPManager::_sendRequestExpectAck(MavlinkFTP::Request* request)
1164 _ackOrNakTimeoutTimer.start();
1168 request->hdr.seqNumber = _expectedIncomingSeqNumber + 1;
1169 _expectedIncomingSeqNumber += 2;
1176 sharedLink->mavlinkChannel(),
1184 qCDebug(FTPManagerLog) <<
"_sendRequestExpectAck No primary link. Allowing timeout to fail sequence.";
1188bool FTPManager::_parseURI(uint8_t fromCompId,
const QString& uri, QString& parsedURI, uint8_t& compId)
1191 compId = (fromCompId == MAV_COMP_ID_ALL) ? (uint8_t)MAV_COMP_ID_AUTOPILOT1 : fromCompId;
1195 if (parsedURI.startsWith(ftpPrefix, Qt::CaseInsensitive)) {
1196 parsedURI = parsedURI.right(parsedURI.length() - ftpPrefix.length() + 1);
1198 if (parsedURI.contains(
"://")) {
1199 qCWarning(FTPManagerLog) <<
"Incorrect uri scheme or format" << uri;
1204 QRegularExpression regEx(
"^/??\\[\\;comp\\=(\\d+)\\]");
1205 QRegularExpressionMatch match = regEx.match(parsedURI);
1206 if (match.hasMatch()) {
1208 compId = match.captured(1).toUInt(&ok);
1210 qCWarning(FTPManagerLog) <<
"Incorrect format for component id" << uri;
1214 qCDebug(FTPManagerLog) <<
"Found compId in MAVLink FTP URI: " << compId;
1215 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()
static MAVLinkProtocol * instance()
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)