FTPManager.cc 29.2 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26
/****************************************************************************
 *
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/


#include "FTPManager.h"
#include "QGC.h"
#include "MAVLinkProtocol.h"
#include "Vehicle.h"
#include "QGCApplication.h"

#include <QFile>
#include <QDir>
#include <string>

QGC_LOGGING_CATEGORY(FTPManagerLog, "FTPManagerLog")

FTPManager::FTPManager(Vehicle* vehicle)
    : QObject   (vehicle)
    , _vehicle  (vehicle)
{
27 28 29 30 31 32 33
    _ackTimer.setSingleShot(true);
    if (qgcApp()->runningUnitTests()) {
        // Mock link responds immediately if at all
        _ackTimer.setInterval(10);
    } else {
        _ackTimer.setInterval(_ackTimerTimeoutMsecs);
    }
34 35 36 37 38 39 40 41 42 43
    connect(&_ackTimer, &QTimer::timeout, this, &FTPManager::_ackTimeout);
    
    _lastOutgoingRequest.hdr.seqNumber = 0;
    
    // Make sure we don't have bad structure packing
    Q_ASSERT(sizeof(MavlinkFTP::RequestHeader) == 12);
}

void FTPManager::_handlOpenFileROAck(MavlinkFTP::Request* ack)
{
44
    qCDebug(FTPManagerLog) << QString("_handlOpenFileROAck: _waitState(%1) _readFileLength(%3)").arg(MavlinkFTP::opCodeToString(_waitState)).arg(ack->openFileLength);
45
    
46 47
    if (_waitState != MavlinkFTP::kCmdOpenFileRO) {
        qCDebug(FTPManagerLog) << "Received OpenFileRO Ack while not waiting for it";
48 49 50 51
        return;
    }

    if (ack->hdr.size != sizeof(uint32_t)) {
52 53
        qCDebug(FTPManagerLog) << "_handlOpenFileROAck: ack->hdr.size != sizeof(uint32_t)" << ack->hdr.size << sizeof(uint32_t);
        _downloadComplete(tr("Download failed"));
54 55 56
        return;
    }

57 58 59 60 61 62 63 64 65 66 67 68 69
    _downloadState.reset();

    _waitState                          = MavlinkFTP::kCmdBurstReadFile;
    _activeSession                      = ack->hdr.session;
    _downloadState.fileSize             = ack->openFileLength;
    _downloadState.expectedBurstOffset  = 0;

    _downloadState.file.setFileName(_downloadState.toDir.filePath(_downloadState.fileName));
    if (!_downloadState.file.open(QFile::WriteOnly | QFile::Truncate)) {
        qCDebug(FTPManagerLog) << "_handlOpenFileROAck: _downloadState.file open failed" << _downloadState.file.errorString();
        _downloadComplete(tr("Download failed"));
        return;
    }
70 71 72

    MavlinkFTP::Request request;
    request.hdr.session = _activeSession;
73 74
    request.hdr.opcode  = MavlinkFTP::kCmdBurstReadFile;
    request.hdr.offset  = _downloadState.expectedBurstOffset;
75 76 77 78
    request.hdr.size    = sizeof(request.data);
    _sendRequestExpectAck(&request);
}

79
void FTPManager::_requestMissingBurstData()
80
{
81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100
    MavlinkFTP::Request request;

    if (_downloadState.missingData.count()) {
        MissingData_t& missingData = _downloadState.missingData.first();

        uint32_t cBytesToRead = qMin((uint32_t)sizeof(request.data), missingData.cBytes);

        qCDebug(FTPManagerLog) << "_requestMissingBurstData: offset:cBytesToRead" << missingData.offset << cBytesToRead;

        request.hdr.session                 = _activeSession;
        request.hdr.opcode                  = MavlinkFTP::kCmdReadFile;
        request.hdr.offset                  = missingData.offset;
        request.hdr.size                    = cBytesToRead;
        _waitState                          = MavlinkFTP::kCmdReadFile;
        _downloadState.retryCount           = 0;
        _downloadState.expectedReadOffset   = request.hdr.offset;

        if (cBytesToRead < missingData.cBytes) {
            missingData.offset += cBytesToRead;
            missingData.cBytes -= cBytesToRead;
101
        } else {
102
            _downloadState.missingData.takeFirst();
103 104
        }
    } else {
105 106 107 108 109 110
        qCDebug(FTPManagerLog) << "_requestMissingBurstData: starting next burst" << _downloadState.expectedBurstOffset;
        request.hdr.session = _activeSession;
        request.hdr.opcode  = MavlinkFTP::kCmdBurstReadFile;
        request.hdr.offset  = _downloadState.expectedBurstOffset;
        request.hdr.size    = sizeof(request.data);
        _waitState = MavlinkFTP::kCmdBurstReadFile;
111 112 113 114 115 116 117 118 119 120 121
    }

    _sendRequestExpectAck(&request);
}

/// Closes out a download session by writing the file and doing cleanup.
///     @param success true: successful download completion, false: error during download
void FTPManager::_downloadComplete(const QString& errorMsg)
{
    qCDebug(FTPManagerLog) << QString("_downloadComplete: errorMsg(%1)").arg(errorMsg);
    
122
    QString downloadFilePath    = _downloadState.toDir.absoluteFilePath(_downloadState.fileName);
123 124
    QString error               = errorMsg;

125
    _ackTimer.stop();
126 127 128
    _waitState = MavlinkFTP::kCmdNone;

    if (error.isEmpty()) {
129
        _downloadState.file.close();
130 131
    }
    
132
    _downloadState.reset();
133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149
    _sendResetCommand(); // Close the open session
    emit downloadComplete(downloadFilePath, error);
}

/// Closes out an upload session doing cleanup.
///     @param success true: successful upload completion, false: error during download
void FTPManager::_uploadComplete(const QString& errorMsg)
{
    qCDebug(FTPManagerLog) << QString("_uploadComplete: errorMsg(%1)").arg(errorMsg);

    _waitState      = MavlinkFTP::kCmdNone;
    _writeFileSize  = 0;
    _writeFileAccumulator.clear();
    _sendResetCommand();
    emit uploadComplete(errorMsg);
}

150 151
// We only do read files to fill in holes from a burst read
void FTPManager::_handleReadFileAck(MavlinkFTP::Request* ack)
152 153 154 155 156
{
    if (ack->hdr.session != _activeSession) {
        return;
    }

157
    qCDebug(FTPManagerLog) << "_handleReadFileAck: offset:size" << ack->hdr.offset << ack->hdr.size;
158

159 160 161 162 163 164
    if (ack->hdr.offset != _downloadState.expectedReadOffset) {
        if (++_downloadState.retryCount > _maxRetry) {
            qCDebug(FTPManagerLog) << QString("_handleReadFileAck: retries exceeded");
            _downloadComplete(tr("Download failed: Unable to retrieve specified file contents"));
            return;
        }
165

166 167
        // Ask for current offset again
        qCDebug(FTPManagerLog) << QString("_handleReadFileAck: retry retryCount(%1) offset(%2)").arg(_downloadState.retryCount).arg(_downloadState.expectedReadOffset);
168 169 170
        MavlinkFTP::Request request;
        request.hdr.session = _activeSession;
        request.hdr.opcode  = _waitState;
171
        request.hdr.offset  = _downloadState.expectedReadOffset;
172 173
        request.hdr.size    = 0;
        _sendRequestExpectAck(&request);
174 175 176 177 178 179 180 181
        return;
    }

    _downloadState.file.seek(ack->hdr.offset);
    int bytesWritten = _downloadState.file.write((const char*)ack->data, ack->hdr.size);
    if (bytesWritten != ack->hdr.size) {
        _downloadComplete(tr("Download failed: Error saving file"));
        return;
182
    }
183 184 185 186 187 188 189 190
    _downloadState.bytesWritten += ack->hdr.size;
    
    if (_downloadState.fileSize != 0) {
        emit commandProgress(100 * ((float)(_downloadState.bytesWritten) / (float)_downloadState.fileSize));
    }

    // Move on to fill in possible next hole
    _requestMissingBurstData();
191 192
}

193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236
void FTPManager::_handleBurstReadFileAck(MavlinkFTP::Request* ack)
{
    if (ack->hdr.session != _activeSession) {
        return;
    }

    qCDebug(FTPManagerLog) << QString("_handleBurstReadFileAck: offset(%1) size(%2) burstComplete(%3)").arg(ack->hdr.offset).arg(ack->hdr.size).arg(ack->hdr.burstComplete);

    if (ack->hdr.offset != _downloadState.expectedBurstOffset) {
        if (ack->hdr.offset > _downloadState.expectedBurstOffset) {
            MissingData_t missingData;
            missingData.offset = _downloadState.expectedBurstOffset;
            missingData.cBytes = ack->hdr.offset - _downloadState.expectedBurstOffset;
            _downloadState.missingData.append(missingData);
            qCDebug(FTPManagerLog) << "_handleBurstReadFileAck: adding missing data offset:cBytes" << missingData.offset << missingData.cBytes;
        } else {
            qCDebug(FTPManagerLog) << "_handleBurstReadFileAck: received offset less than expected offset received:expected" << ack->hdr.offset << _downloadState.expectedBurstOffset;
            _ackTimer.start();
            return;
        }
    }

    _downloadState.file.seek(ack->hdr.offset);
    int bytesWritten = _downloadState.file.write((const char*)ack->data, ack->hdr.size);
    if (bytesWritten != ack->hdr.size) {
        _downloadComplete(tr("Download failed: Error saving file"));
        return;
    }
    _downloadState.bytesWritten += ack->hdr.size;
    _downloadState.expectedBurstOffset = ack->hdr.offset + ack->hdr.size;

    if (_downloadState.fileSize != 0) {
        emit commandProgress(100 * ((float)(_downloadState.bytesWritten) / (float)_downloadState.fileSize));
    }

    if (ack->hdr.burstComplete) {
        _requestMissingBurstData();
    } else {
        // Still within a burst, next ack should come automatically
        _ackTimer.start();
    }
}

void FTPManager::_listAckResponse(MavlinkFTP::Request* /*listAck*/)
237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297
{
#if 0
    if (listAck->hdr.offset != _listOffset) {
        // this is a real error (directory listing is synchronous), no need to retransmit
        _currentOperation = kCOIdle;
        _emitErrorMessage(tr("List: Offset returned (%1) differs from offset requested (%2)").arg(listAck->hdr.offset).arg(_listOffset));
        return;
    }

    uint8_t offset = 0;
    uint8_t cListEntries = 0;
    uint8_t cBytes = listAck->hdr.size;

    // parse filenames out of the buffer
    while (offset < cBytes) {
        const char * ptr = ((const char *)listAck->data) + offset;

        // get the length of the name
        uint8_t cBytesLeft = cBytes - offset;
        uint8_t nlen = static_cast<uint8_t>(strnlen(ptr, cBytesLeft));
        if ((*ptr == 'S' && nlen > 1) || (*ptr != 'S' && nlen < 2)) {
            _currentOperation = kCOIdle;
            _emitErrorMessage(tr("Incorrectly formed list entry: '%1'").arg(ptr));
            return;
        } else if (nlen == cBytesLeft) {
            _currentOperation = kCOIdle;
            _emitErrorMessage(tr("Missing NULL termination in list entry"));
            return;
        }

        // Returned names are prepended with D for directory, F for file, S for skip
        if (*ptr == 'F' || *ptr == 'D') {
            // put it in the view
            _emitListEntry(ptr);
        } else if (*ptr == 'S') {
            // do nothing
        } else {
            qDebug() << "unknown entry" << ptr;
        }

        // account for the name + NUL
        offset += nlen + 1;

        cListEntries++;
    }

    if (listAck->hdr.size == 0 || cListEntries == 0) {
        // Directory is empty, we're done
        Q_ASSERT(listAck->hdr.opcode == MavlinkFTP::kRspAck);
        _currentOperation = kCOIdle;
        emit commandComplete();
    } else {
        // Possibly more entries to come, need to keep trying till we get EOF
        _currentOperation = kCOList;
        _listOffset += cListEntries;
        _sendListCommand();
    }
#endif
}

/// @brief Respond to the Ack associated with the create command.
298
void FTPManager::_createAckResponse(MavlinkFTP::Request* /*createAck*/)
299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315
{
#if 0
    qCDebug(FTPManagerLog) << "_createAckResponse";
    
    _currentOperation = kCOWrite;
    _activeSession = createAck->hdr.session;

    // Start the sequence of write commands from the beginning of the file

    _writeOffset = 0;
    _writeSize = 0;
    
    _writeFileDatablock();
#endif
}

/// @brief Respond to the Ack associated with the write command.
316
void FTPManager::_writeAckResponse(MavlinkFTP::Request* /*writeAck*/)
317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381
{
#if 0
    if(_writeOffset + _writeSize >= _writeFileSize){
        _closeUploadSession(true /* success */);
        return;
    }

    if (writeAck->hdr.session != _activeSession) {
        _closeUploadSession(false /* failure */);
        _emitErrorMessage(tr("Write: Incorrect session returned"));
        return;
    }

    if (writeAck->hdr.offset != _writeOffset) {
        _closeUploadSession(false /* failure */);
        _emitErrorMessage(tr("Write: Offset returned (%1) differs from offset requested (%2)").arg(writeAck->hdr.offset).arg(_writeOffset));
        return;
    }

    if (writeAck->hdr.size != sizeof(uint32_t)) {
        _closeUploadSession(false /* failure */);
        _emitErrorMessage(tr("Write: Returned invalid size of write size data"));
        return;
    }


    if( writeAck->writeFileLength !=_writeSize) {
        _closeUploadSession(false /* failure */);
        _emitErrorMessage(tr("Write: Size returned (%1) differs from size requested (%2)").arg(writeAck->writeFileLength).arg(_writeSize));
        return;
    }

    _writeFileDatablock();
#endif
}

/// @brief Send next write file data block.
void FTPManager::_writeFileDatablock(void)
{
#if 0
    if (_writeOffset + _writeSize >= _writeFileSize){
        _closeUploadSession(true /* success */);
        return;
    }

    _writeOffset += _writeSize;

    MavlinkFTP::Request request;
    request.hdr.session = _activeSession;
    request.hdr.opcode = MavlinkFTP::kCmdWriteFile;
    request.hdr.offset = _writeOffset;

    if(_writeFileSize -_writeOffset > sizeof(request.data) )
        _writeSize = sizeof(request.data);
    else
        _writeSize = _writeFileSize - _writeOffset;

    request.hdr.size = _writeSize;

    memcpy(request.data, &_writeFileAccumulator.data()[_writeOffset], _writeSize);

    _sendRequestExpectAck(&request);
#endif
}

382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470
void FTPManager::_handleAck(MavlinkFTP::Request* ack)
{

    switch (ack->hdr.req_opcode) {
    case MavlinkFTP::kCmdOpenFileRO:
        _handlOpenFileROAck(ack);
        break;
    case MavlinkFTP::kCmdReadFile:
        _handleReadFileAck(ack);
        break;
    case MavlinkFTP::kCmdBurstReadFile:
        _handleBurstReadFileAck(ack);
        break;

#if 0
    case MavlinkFTP::kCmdListDirectory:
        _listAckResponse(request);
        break;

    case MavlinkFTP::kCmdOpenFileRO:
    case MavlinkFTP::kCmdOpenFileWO:
        _handlOpenFileROAck(request);
        break;

    case MavlinkFTP::kCmdCreateFile:
        _createAckResponse(request);
        break;

    case MavlinkFTP::kCmdWriteFile:
        _writeAckResponse(request);
        break;
#endif
    default:
        // Ack back from operation which does not require additional work
        _waitState = MavlinkFTP::kCmdNone;
        break;
    }
}

void FTPManager::_handleNak(MavlinkFTP::Request* nak)
{
    QString                 errorMsg;
    MavlinkFTP::OpCode_t    requestOpCode = static_cast<MavlinkFTP::OpCode_t>(nak->hdr.req_opcode);
    MavlinkFTP::ErrorCode_t errorCode = static_cast<MavlinkFTP::ErrorCode_t>(nak->data[0]);

    if (errorCode == MavlinkFTP::kErrEOF) {
        qCDebug(FTPManagerLog) << "_handleNak EOF";
        if (requestOpCode == MavlinkFTP::kCmdReadFile && _downloadState.bytesWritten == _downloadState.fileSize) {
            // This could be an EOF on a normal read sequence, or an EOF for a read to fill in holes from a burst read.
            // Either way it means we should be done.
            _downloadComplete(QString());
            return;
        } else if (requestOpCode == MavlinkFTP::kCmdBurstReadFile) {
            // This is an EOF during a burst read, we still have to check for filling in missing data
            if (_downloadState.missingData.count()) {
                // We only call _requestMissingBurstData if there are no missing blocks since _requestMissingBurstData will start a new
                // burst sequence if you call it with no missing blocks which would put us into an infinite loop on EOFs.
                _requestMissingBurstData();
                return;
            } else if (_downloadState.bytesWritten == _downloadState.fileSize) {
                _downloadComplete(QString());
                return;
            }
        }
    }

    // Nak's normally have 1 byte of data for error code, except for MavlinkFTP::kErrFailErrno which has additional byte for errno
    if ((errorCode == MavlinkFTP::kErrFailErrno && nak->hdr.size != 2) || ((errorCode != MavlinkFTP::kErrFailErrno) && nak->hdr.size != 1)) {
        errorMsg = tr("Invalid Nak format");
    } else if (errorCode == MavlinkFTP::kErrFailErrno) {
        errorMsg = tr("errno %1").arg(nak->data[1]);
    } else {
        errorMsg = MavlinkFTP::errorCodeToString(errorCode);
    }

    _waitState = MavlinkFTP::kCmdNone;

    switch (nak->hdr.req_opcode) {
    case MavlinkFTP::kCmdOpenFileRO:
    case MavlinkFTP::kCmdReadFile:
    case MavlinkFTP::kCmdBurstReadFile:
        _downloadComplete(tr("Download failed: %1").arg(errorMsg));
        break;
    default:
        // FIXME: Rest is NYI
        break;
    }
}

471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492
void FTPManager::mavlinkMessageReceived(mavlink_message_t message)
{
    if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) {
        return;
    }

    mavlink_file_transfer_protocol_t data;
    mavlink_msg_file_transfer_protocol_decode(&message, &data);

    // Make sure we are the target system
    int qgcId = qgcApp()->toolbox()->mavlinkProtocol()->getSystemId();
    if (data.target_system != qgcId) {
        return;
    }
    
    MavlinkFTP::Request* request = (MavlinkFTP::Request*)&data.payload[0];

    uint16_t incomingSeqNumber = request->hdr.seqNumber;
    uint16_t expectedSeqNumber = _lastOutgoingRequest.hdr.seqNumber + 1;

    // ignore old/reordered packets (handle wrap-around properly)
    if ((uint16_t)((expectedSeqNumber - 1) - incomingSeqNumber) < (std::numeric_limits<uint16_t>::max()/2)) {
493
        qCDebug(FTPManagerLog) << "Received old packet: expected seq:" << expectedSeqNumber << "got:" << incomingSeqNumber;
494 495 496
        return;
    }

497
    _ackTimer.stop();
498 499 500 501 502 503
    
    qCDebug(FTPManagerLog) << "mavlinkMessageReceived" << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.opcode)) <<  MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.req_opcode));

    if (incomingSeqNumber != expectedSeqNumber) {
        switch (_waitState) {
        case MavlinkFTP::kCmdOpenFileRO:
504 505
            _downloadComplete(tr("Download failed: Unable to handle packet loss"));
            break;
506 507
        case MavlinkFTP::kCmdReadFile:
        case MavlinkFTP::kCmdBurstReadFile:
508 509
            // These can handle packet loss
            break;
510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533
#if 0
        case kCOWrite:
            _closeUploadSession(false /* failure */);
            break;

        case kCOOpenRead:
        case kCOOpenBurst:
        case kCOCreate:
            // We could have an open session hanging around
            _currentOperation = kCOIdle;
            _sendResetCommand();
            break;
#endif
        default:
            // Don't need to do anything special
            _waitState = MavlinkFTP::kCmdNone;
            break;
        }
    }
    
    // Move past the incoming sequence number for next request
    _lastOutgoingRequest.hdr.seqNumber = incomingSeqNumber;

    if (request->hdr.opcode == MavlinkFTP::kRspAck) {
534
        _handleAck(request);
535
    } else if (request->hdr.opcode == MavlinkFTP::kRspNak) {
536
        _handleNak(request);
537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586
    }
}

void FTPManager::listDirectory(const QString& dirPath)
{
    if (_waitState != MavlinkFTP::kCmdNone) {
        _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
        return;
    }

    _dedicatedLink = _vehicle->priorityLink();
    if (!_dedicatedLink) {
        _emitErrorMessage(tr("Command not sent. No Vehicle links."));
        return;
    }

    // initialise the lister
    _listPath           = dirPath;
    _listOffset         = 0;
    _waitState   =      MavlinkFTP::kCmdListDirectory;

    // and send the initial request
    _sendListCommand();
}

void FTPManager::_fillRequestWithString(MavlinkFTP::Request* request, const QString& str)
{
    strncpy((char *)&request->data[0], str.toStdString().c_str(), sizeof(request->data));
    request->hdr.size = static_cast<uint8_t>(strnlen((const char *)&request->data[0], sizeof(request->data)));
}

void FTPManager::_sendListCommand(void)
{
    MavlinkFTP::Request request;

    request.hdr.session = 0;
    request.hdr.opcode = MavlinkFTP::kCmdListDirectory;
    request.hdr.offset = _listOffset;
    request.hdr.size = 0;

    _fillRequestWithString(&request, _listPath);

    qCDebug(FTPManagerLog) << "listDirectory: path:" << _listPath << "offset:" <<  _listOffset;
    
    _sendRequestExpectAck(&request);
}

bool FTPManager::download(const QString& from, const QString& toDir)
{
    qCDebug(FTPManagerLog) << "download from:" << from << "to:" << toDir;
587
    return _downloadWorker(from, toDir);
588 589
}

590
bool FTPManager::_downloadWorker(const QString& from, const QString& toDir)
591 592 593 594 595 596 597 598 599 600 601 602
{
    if (_waitState != MavlinkFTP::kCmdNone) {
        qCDebug(FTPManagerLog) << "Cannot download. Already in another operation";
        return false;
    }

    _dedicatedLink = _vehicle->priorityLink();
    if (!_dedicatedLink) {
        qCDebug(FTPManagerLog) << "Cannot download. Vehicle has no priority link";
        return false;
    }

603 604
    _downloadState.reset();
    _downloadState.toDir.setPath(toDir);
605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623

    QString strippedFrom;
    QString ftpPrefix("mavlinkftp://");
    if (from.startsWith(ftpPrefix, Qt::CaseInsensitive)) {
        strippedFrom = from.right(from.length() - ftpPrefix.length() + 1);
    } else {
        strippedFrom = from;
    }

    // We need to strip off the file name from the fully qualified path. We can't use the usual QDir
    // routines because this path does not exist locally.
    int lastDirSlashIndex;
    for (lastDirSlashIndex=strippedFrom.size()-1; lastDirSlashIndex>=0; lastDirSlashIndex--) {
        if (strippedFrom[lastDirSlashIndex] == '/') {
            break;
        }
    }
    lastDirSlashIndex++; // move past slash

624 625
    _downloadState.fileName = strippedFrom.right(strippedFrom.size() - lastDirSlashIndex);
    _waitState              = MavlinkFTP::kCmdOpenFileRO;
626 627 628 629 630 631 632 633 634 635 636 637 638 639 640

    MavlinkFTP::Request request;
    request.hdr.session = 0;
    request.hdr.opcode  = MavlinkFTP::kCmdOpenFileRO;
    request.hdr.offset  = 0;
    request.hdr.size    = 0;
    _fillRequestWithString(&request, strippedFrom);
    _sendRequestExpectAck(&request);

    return true;
}

/// @brief Uploads the specified file.
///     @param toPath File in UAS to upload to, fully qualified path
///     @param uploadFile Local file to upload from
641
void FTPManager::upload(const QString& /*toPath*/, const QFileInfo& /*uploadFile*/)
642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691
{
#if 0
    if(_currentOperation != kCOIdle){
        _emitErrorMessage(tr("UAS File manager busy. Try again later"));
        return;
    }

    _dedicatedLink = _vehicle->priorityLink();
    if (!_dedicatedLink) {
        _emitErrorMessage(tr("Command not sent. No Vehicle links."));
        return;
    }

    if (toPath.isEmpty()) {
        return;
    }

    if (!uploadFile.isReadable()){
        _emitErrorMessage(tr("File (%1) is not readable for upload").arg(uploadFile.path()));
        return;
    }

    QFile file(uploadFile.absoluteFilePath());
    if (!file.open(QIODevice::ReadOnly)) {
        _emitErrorMessage(tr("Unable to open local file for upload (%1)").arg(uploadFile.absoluteFilePath()));
        return;
    }

    _writeFileAccumulator = file.readAll();
    _writeFileSize = _writeFileAccumulator.size();

    file.close();

    if (_writeFileAccumulator.size() == 0) {
        _emitErrorMessage(tr("Unable to read data from local file (%1)").arg(uploadFile.absoluteFilePath()));
        return;
    }

    _currentOperation = kCOCreate;

    MavlinkFTP::Request request;
    request.hdr.session = 0;
    request.hdr.opcode = MavlinkFTP::kCmdCreateFile;
    request.hdr.offset = 0;
    request.hdr.size = 0;
    _fillRequestWithString(&request, toPath + "/" + uploadFile.fileName());
    _sendRequestExpectAck(&request);
#endif
}

692
void FTPManager::createDirectory(const QString& /*directory*/)
693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734
{
#if 0
    if(_currentOperation != kCOIdle){
        _emitErrorMessage(tr("UAS File manager busy. Try again later"));
        return;
    }

    _currentOperation = kCOCreateDir;

    MavlinkFTP::Request request;
    request.hdr.session = 0;
    request.hdr.opcode = MavlinkFTP::kCmdCreateDirectory;
    request.hdr.offset = 0;
    request.hdr.size = 0;
    _fillRequestWithString(&request, directory);
    _sendRequestExpectAck(&request);
#endif
}

/// @brief Sends a command which only requires an opcode and no additional data
///     @param opcode Opcode to send
///     @param newOpState State to put state machine into
/// @return TRUE: command sent, FALSE: command not sent, waiting for previous command to finish
bool FTPManager::_sendOpcodeOnlyCmd(MavlinkFTP::OpCode_t opcode, MavlinkFTP::OpCode_t newWaitState)
{
    if (_waitState != MavlinkFTP::kCmdNone) {
        // Can't have multiple commands in play at the same time
        return false;
    }

    _waitState = newWaitState;

    MavlinkFTP::Request request;
    request.hdr.session = 0;
    request.hdr.opcode  = opcode;
    request.hdr.offset  = 0;
    request.hdr.size    = 0;
    _sendRequestExpectAck(&request);

    return true;
}

735
void FTPManager::_ackTimeout(void)
736
{
737
    qCDebug(FTPManagerLog) << "_ackTimeout" << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(_waitState));
738

739 740 741 742 743 744 745 746 747 748
    switch (_waitState) {
    case MavlinkFTP::kCmdReadFile:
        // FIXME: retry count?
        // Resend last request
        _lastOutgoingRequest.hdr.seqNumber--;
        _sendRequestExpectAck(&_lastOutgoingRequest);
        return;
    default:
        break;
    }
749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776

#if 0
    if (++_ackNumTries <= _ackTimerMaxRetries) {
        qCDebug(FTPManagerLog) << "ack timeout - retrying";
        if (_currentOperation == kCOBurst) {
            // for burst downloads try to initiate a new burst
            MavlinkFTP::Request request;
            request.hdr.session = _activeSession;
            request.hdr.opcode = MavlinkFTP::kCmdBurstReadFile;
            request.hdr.offset = _downloadOffset;
            request.hdr.size = 0;
            request.hdr.seqNumber = ++_lastOutgoingRequest.hdr.seqNumber;

            _sendRequestNoAck(&request);
        } else {
            _sendRequestNoAck(&_lastOutgoingRequest);
        }
        return;
    }
#endif

    // Make sure to set _currentOperation state before emitting error message. Code may respond
    // to error message signal by sending another command, which will fail if state is not back
    // to idle. FileView UI works this way with the List command.

    switch (_waitState) {
    case MavlinkFTP::kCmdOpenFileRO:
    case MavlinkFTP::kCmdBurstReadFile:
777 778
    case MavlinkFTP::kCmdReadFile:
        _downloadComplete(tr("Download failed: Vehicle did not respond to %1").arg(MavlinkFTP::opCodeToString(_waitState)));
779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812
        break;
#if 0
        // FIXME: NYI
    case kCOOpenRead:
    case kCOOpenBurst:
        _currentOperation = kCOIdle;
        _emitErrorMessage(tr("Timeout waiting for ack: Download failed"));
        _sendResetCommand();
        break;

    case kCOCreate:
        _currentOperation = kCOIdle;
        _emitErrorMessage(tr("Timeout waiting for ack: Upload failed"));
        _sendResetCommand();
        break;

    case kCOWrite:
        _closeUploadSession(false /* failure */);
        _emitErrorMessage(tr("Timeout waiting for ack: Upload failed"));
        break;
#endif
    default:
    {
        MavlinkFTP::OpCode_t    _lastCommand = _waitState;
        _waitState = MavlinkFTP::kCmdNone;
        _emitErrorMessage(QString("Timeout waiting for ack: Command failed (%1)").arg(MavlinkFTP::opCodeToString(_lastCommand)));
    }
        break;
    }
}

void FTPManager::_sendResetCommand(void)
{
    MavlinkFTP::Request request;
813 814 815
    request.hdr.opcode  = MavlinkFTP::kCmdResetSessions;
    request.hdr.size    = 0;
    _waitState          = MavlinkFTP::kCmdResetSessions;
816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832
    _sendRequestExpectAck(&request);
}

void FTPManager::_emitErrorMessage(const QString& msg)
{
    qCDebug(FTPManagerLog) << "Error:" << msg;
    emit commandError(msg);
}

void FTPManager::_emitListEntry(const QString& entry)
{
    qCDebug(FTPManagerLog) << "_emitListEntry" << entry;
    emit listEntry(entry);
}

void FTPManager::_sendRequestExpectAck(MavlinkFTP::Request* request)
{
833
    _ackTimer.start();
834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862
    
    request->hdr.seqNumber = ++_lastOutgoingRequest.hdr.seqNumber;
    qCDebug(FTPManagerLog) << "_sendRequestExpectAck opcode:" << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.opcode)) << "seqNumber:" << request->hdr.seqNumber;

    if (request->hdr.size <= sizeof(request->data)) {
        memcpy(&_lastOutgoingRequest, request, sizeof(MavlinkFTP::RequestHeader) + request->hdr.size);
    } else {
        // FIXME: Shouldn't this fail something?
        qCCritical(FTPManagerLog) << "request length too long:" << request->hdr.size;
    }
    
    _sendRequestNoAck(request);
}

void FTPManager::_sendRequestNoAck(MavlinkFTP::Request* request)
{
    qCDebug(FTPManagerLog) << "_sendRequestNoAck opcode:" << MavlinkFTP::opCodeToString(static_cast<MavlinkFTP::OpCode_t>(request->hdr.opcode));

    mavlink_message_t message;
    mavlink_msg_file_transfer_protocol_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
                                                 qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
                                                 _dedicatedLink->mavlinkChannel(),
                                                 &message,
                                                 0,                                                     // Target network, 0=broadcast?
                                                 _vehicle->id(),
                                                 MAV_COMP_ID_AUTOPILOT1,
                                                 (uint8_t*)request);                                    // Payload
    _vehicle->sendMessageOnLinkThreadSafe(_dedicatedLink, message);
}