FileManager.cc 29.9 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
9

10

11
#include "FileManager.h"
12
#include "QGC.h"
Lorenz Meier's avatar
Lorenz Meier committed
13
#include "MAVLinkProtocol.h"
14
#include "Vehicle.h"
15
#include "QGCApplication.h"
Lorenz Meier's avatar
Lorenz Meier committed
16 17 18

#include <QFile>
#include <QDir>
none's avatar
none committed
19
#include <string>
Lorenz Meier's avatar
Lorenz Meier committed
20

21
QGC_LOGGING_CATEGORY(FileManagerLog, "FileManagerLog")
22

23 24 25 26
FileManager::FileManager(QObject* parent, Vehicle* vehicle)
    : QObject(parent)
    , _currentOperation(kCOIdle)
    , _vehicle(vehicle)
27
    , _dedicatedLink(nullptr)
28
    , _activeSession(0)
29 30
    , _missingDownloadedBytes(0)
    , _downloadingMissingParts(false)
31
    , _systemIdQGC(0)
Lorenz Meier's avatar
Lorenz Meier committed
32
{
33
    connect(&_ackTimer, &QTimer::timeout, this, &FileManager::_ackTimeout);
34
    
35 36
    _lastOutgoingRequest.hdr.seqNumber = 0;

37
    _systemIdServer = _vehicle->id();
38 39
    
    // Make sure we don't have bad structure packing
40
    Q_ASSERT(sizeof(RequestHeader) == 12);
Lorenz Meier's avatar
Lorenz Meier committed
41 42
}

Don Gagne's avatar
Don Gagne committed
43
/// Respond to the Ack associated with the Open command with the next read command.
44
void FileManager::_openAckResponse(Request* openAck)
45
{
Don Gagne's avatar
Don Gagne committed
46 47 48
    qCDebug(FileManagerLog) << QString("_openAckResponse: _currentOperation(%1) _readFileLength(%2)").arg(_currentOperation).arg(openAck->openFileLength);
    
	Q_ASSERT(_currentOperation == kCOOpenRead || _currentOperation == kCOOpenBurst);
49
	_currentOperation = _currentOperation == kCOOpenRead ? kCORead : kCOBurst;
50
    _activeSession = openAck->hdr.session;
51 52 53
    
    // File length comes back in data
    Q_ASSERT(openAck->hdr.size == sizeof(uint32_t));
Don Gagne's avatar
Don Gagne committed
54
    _downloadFileSize = openAck->openFileLength;
55 56
    
    // Start the sequence of read commands
57

Don Gagne's avatar
Don Gagne committed
58
    _downloadOffset = 0;            // Start reading at beginning of file
59
    _readFileAccumulator.clear();   // Start with an empty file
60 61 62
    _missingDownloadedBytes = 0;
    _downloadingMissingParts = false;
    _missingData.clear();
63

64 65
    Request request;
    request.hdr.session = _activeSession;
66 67 68
	Q_ASSERT(_currentOperation == kCORead || _currentOperation == kCOBurst);
	request.hdr.opcode = _currentOperation == kCORead ? kCmdReadFile : kCmdBurstReadFile;
    request.hdr.offset = _downloadOffset;
69
    request.hdr.size = sizeof(request.data);
70

71 72 73
    _sendRequest(&request);
}

74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104
/// request the next missing part of a (partially) downloaded file
void FileManager::_requestMissingData()
{
    if (_missingData.empty()) {
        _downloadingMissingParts = false;
        _missingDownloadedBytes = 0;
        // there might be more data missing at the end
        if ((uint32_t)_readFileAccumulator.length() != _downloadFileSize) {
            _downloadOffset = _readFileAccumulator.length();
            qCDebug(FileManagerLog) << QString("_requestMissingData: missing parts done, downloadOffset(%1) downloadFileSize(%2)")
                    .arg(_downloadOffset).arg(_downloadFileSize);
        } else {
            _closeDownloadSession(true);
            return;
        }
    } else {
        qCDebug(FileManagerLog) << QString("_requestMissingData: offset(%1) size(%2)").arg(_missingData.head().offset).arg(_missingData.head().size);

        _downloadOffset = _missingData.head().offset;
    }

    Request request;
    _currentOperation = kCORead;
    request.hdr.session = _activeSession;
    request.hdr.opcode = kCmdReadFile;
    request.hdr.offset = _downloadOffset;
    request.hdr.size = sizeof(request.data);

    _sendRequest(&request);
}

Don Gagne's avatar
Don Gagne committed
105
/// Closes out a download session by writing the file and doing cleanup.
106
///     @param success true: successful download completion, false: error during download
107
void FileManager::_closeDownloadSession(bool success)
108
{
109
    qCDebug(FileManagerLog) << QString("_closeDownloadSession: success(%1) missingBytes(%2)").arg(success).arg(_missingDownloadedBytes);
Don Gagne's avatar
Don Gagne committed
110 111 112
    
    _currentOperation = kCOIdle;
    
113
    if (success) {
114 115 116 117 118 119 120 121
        if (_missingDownloadedBytes > 0 || (uint32_t)_readFileAccumulator.length() < _downloadFileSize) {
            // we're not done yet: request the missing parts individually (either we had missing parts or
            // the last (few) packets right before the EOF got dropped)
            _downloadingMissingParts = true;
            _requestMissingData();
            return;
        }

122
        QString downloadFilePath = _readFileDownloadDir.absoluteFilePath(_readFileDownloadFilename);
123

124 125 126 127 128
        QFile file(downloadFilePath);
        if (!file.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
            _emitErrorMessage(tr("Unable to open local file for writing (%1)").arg(downloadFilePath));
            return;
        }
129

130 131 132 133 134 135 136
        qint64 bytesWritten = file.write((const char *)_readFileAccumulator, _readFileAccumulator.length());
        if (bytesWritten != _readFileAccumulator.length()) {
            file.close();
            _emitErrorMessage(tr("Unable to write data to local file (%1)").arg(downloadFilePath));
            return;
        }
        file.close();
137

Don Gagne's avatar
Don Gagne committed
138
        emit commandComplete();
139
    }
Don Gagne's avatar
Don Gagne committed
140
    
Don Gagne's avatar
Don Gagne committed
141 142
    _readFileAccumulator.clear();
    
143
    // Close the open session
Don Gagne's avatar
Don Gagne committed
144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162
    _sendResetCommand();
}

/// Closes out an upload session doing cleanup.
///     @param success true: successful upload completion, false: error during download
void FileManager::_closeUploadSession(bool success)
{
    qCDebug(FileManagerLog) << QString("_closeUploadSession: success(%1)").arg(success);
    
    _currentOperation = kCOIdle;
    _writeFileAccumulator.clear();
    _writeFileSize = 0;
    
    if (success) {
        emit commandComplete();
    }
    
    // Close the open session
    _sendResetCommand();
163 164
}

165 166 167
/// Respond to the Ack associated with the Read or Stream commands.
///		@param readFile: true: read file, false: stream file
void FileManager::_downloadAckResponse(Request* readAck, bool readFile)
168 169
{
    if (readAck->hdr.session != _activeSession) {
Don Gagne's avatar
Don Gagne committed
170
        _closeDownloadSession(false /* failure */);
171
        _emitErrorMessage(tr("Download: Incorrect session returned"));
172 173
        return;
    }
174

175
    if (readAck->hdr.offset != _downloadOffset) {
176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194
        if (readFile) {
            _closeDownloadSession(false /* failure */);
            _emitErrorMessage(tr("Download: Offset returned (%1) differs from offset requested/expected (%2)").arg(readAck->hdr.offset).arg(_downloadOffset));
            return;
        } else { // burst
            if (readAck->hdr.offset < _downloadOffset) { // old data: ignore it
                _setupAckTimeout();
                return;
            }
            // keep track of missing data chunks
            MissingData missingData;
            missingData.offset = _downloadOffset;
            missingData.size = readAck->hdr.offset - _downloadOffset;
            _missingData.push_back(missingData);
            _missingDownloadedBytes += readAck->hdr.offset - _downloadOffset;
            qCDebug(FileManagerLog) << QString("_downloadAckResponse: missing data: offset(%1) size(%2)").arg(missingData.offset).arg(missingData.size);
            _downloadOffset = readAck->hdr.offset;
            _readFileAccumulator.resize(_downloadOffset); // placeholder for the missing data
        }
195
    }
196 197
    
    qCDebug(FileManagerLog) << QString("_downloadAckResponse: offset(%1) size(%2) burstComplete(%3)").arg(readAck->hdr.offset).arg(readAck->hdr.size).arg(readAck->hdr.burstComplete);
198

199 200 201 202 203 204 205 206 207 208 209 210 211 212
    if (_downloadingMissingParts) {
        Q_ASSERT(_missingData.head().offset == _downloadOffset);
        _missingDownloadedBytes -= readAck->hdr.size;
        _readFileAccumulator.replace(_downloadOffset, readAck->hdr.size, (const char*)readAck->data, readAck->hdr.size);
        if (_missingData.head().size <= readAck->hdr.size) {
            _missingData.pop_front();
        } else {
            _missingData.head().size -= readAck->hdr.size;
            _missingData.head().offset += readAck->hdr.size;
        }
    } else {
        _downloadOffset += readAck->hdr.size;
        _readFileAccumulator.append((const char*)readAck->data, readAck->hdr.size);
    }
Don Gagne's avatar
Don Gagne committed
213 214
    
    if (_downloadFileSize != 0) {
215
        emit commandProgress(100 * ((float)(_readFileAccumulator.length() - _missingDownloadedBytes) / (float)_downloadFileSize));
Don Gagne's avatar
Don Gagne committed
216
    }
217

218 219 220
    if (_downloadingMissingParts) {
        _requestMissingData();
    } else if (readFile || readAck->hdr.burstComplete) {
Don Gagne's avatar
Don Gagne committed
221
        // Possibly still more data to read, send next read request
222

Don Gagne's avatar
Don Gagne committed
223 224 225 226 227
        Request request;
        request.hdr.session = _activeSession;
        request.hdr.opcode = readFile ? kCmdReadFile : kCmdBurstReadFile;
        request.hdr.offset = _downloadOffset;
        request.hdr.size = 0;
228

Don Gagne's avatar
Don Gagne committed
229 230 231 232
        _sendRequest(&request);
    } else if (!readFile) {
        // Streaming, so next ack should come automatically
        _setupAckTimeout();
233 234 235 236
    }
}

/// @brief Respond to the Ack associated with the List command.
237
void FileManager::_listAckResponse(Request* listAck)
238 239
{
    if (listAck->hdr.offset != _listOffset) {
240
        // this is a real error (directory listing is synchronous), no need to retransmit
241 242 243 244
        _currentOperation = kCOIdle;
        _emitErrorMessage(tr("List: Offset returned (%1) differs from offset requested (%2)").arg(listAck->hdr.offset).arg(_listOffset));
        return;
    }
245

246 247 248
    uint8_t offset = 0;
    uint8_t cListEntries = 0;
    uint8_t cBytes = listAck->hdr.size;
249

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

254 255
        // get the length of the name
        uint8_t cBytesLeft = cBytes - offset;
Don Gagne's avatar
Don Gagne committed
256
        uint8_t nlen = static_cast<uint8_t>(strnlen(ptr, cBytesLeft));
257
        if ((*ptr == 'S' && nlen > 1) || (*ptr != 'S' && nlen < 2)) {
258 259 260 261 262 263 264 265
            _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;
        }
266

267
        // Returned names are prepended with D for directory, F for file, S for skip
268 269
        if (*ptr == 'F' || *ptr == 'D') {
            // put it in the view
270
            _emitListEntry(ptr);
271 272
        } else if (*ptr == 'S') {
            // do nothing
273 274
        } else {
            qDebug() << "unknown entry" << ptr;
275
        }
276

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

280 281 282
        cListEntries++;
    }

Don Gagne's avatar
Don Gagne committed
283
    if (listAck->hdr.size == 0 || cListEntries == 0) {
284 285 286
        // Directory is empty, we're done
        Q_ASSERT(listAck->hdr.opcode == kRspAck);
        _currentOperation = kCOIdle;
Don Gagne's avatar
Don Gagne committed
287
        emit commandComplete();
288 289
    } else {
        // Possibly more entries to come, need to keep trying till we get EOF
290 291 292
        _currentOperation = kCOList;
        _listOffset += cListEntries;
        _sendListCommand();
293 294 295
    }
}

296
/// @brief Respond to the Ack associated with the create command.
297
void FileManager::_createAckResponse(Request* createAck)
298
{
Don Gagne's avatar
Don Gagne committed
299 300
    qCDebug(FileManagerLog) << "_createAckResponse";
    
301 302 303
    _currentOperation = kCOWrite;
    _activeSession = createAck->hdr.session;

Don Gagne's avatar
Don Gagne committed
304
    // Start the sequence of write commands from the beginning of the file
305

Don Gagne's avatar
Don Gagne committed
306
    _writeOffset = 0;
307
    _writeSize = 0;
Don Gagne's avatar
Don Gagne committed
308
    
309 310 311 312
    _writeFileDatablock();
}

/// @brief Respond to the Ack associated with the write command.
313
void FileManager::_writeAckResponse(Request* writeAck)
314
{
315
    if(_writeOffset + _writeSize >= _writeFileSize){
Don Gagne's avatar
Don Gagne committed
316
        _closeUploadSession(true /* success */);
317
        return;
318 319
    }

320
    if (writeAck->hdr.session != _activeSession) {
Don Gagne's avatar
Don Gagne committed
321
        _closeUploadSession(false /* failure */);
322 323 324 325 326
        _emitErrorMessage(tr("Write: Incorrect session returned"));
        return;
    }

    if (writeAck->hdr.offset != _writeOffset) {
Don Gagne's avatar
Don Gagne committed
327
        _closeUploadSession(false /* failure */);
328 329 330 331
        _emitErrorMessage(tr("Write: Offset returned (%1) differs from offset requested (%2)").arg(writeAck->hdr.offset).arg(_writeOffset));
        return;
    }

332
    if (writeAck->hdr.size != sizeof(uint32_t)) {
Don Gagne's avatar
Don Gagne committed
333
        _closeUploadSession(false /* failure */);
334
        _emitErrorMessage(tr("Write: Returned invalid size of write size data"));
335 336 337
        return;
    }

338

Don Gagne's avatar
Don Gagne committed
339 340
    if( writeAck->writeFileLength !=_writeSize) {
        _closeUploadSession(false /* failure */);
341
        _emitErrorMessage(tr("Write: Size returned (%1) differs from size requested (%2)").arg(writeAck->writeFileLength).arg(_writeSize));
342 343 344 345 346 347 348
        return;
    }

    _writeFileDatablock();
}

/// @brief Send next write file data block.
349
void FileManager::_writeFileDatablock(void)
350
{
Don Gagne's avatar
Don Gagne committed
351 352
    if (_writeOffset + _writeSize >= _writeFileSize){
        _closeUploadSession(true /* success */);
353
        return;
354 355
    }

356 357
    _writeOffset += _writeSize;

358 359 360 361 362
    Request request;
    request.hdr.session = _activeSession;
    request.hdr.opcode = kCmdWriteFile;
    request.hdr.offset = _writeOffset;

363
    if(_writeFileSize -_writeOffset > sizeof(request.data) )
364 365
        _writeSize = sizeof(request.data);
    else
366
        _writeSize = _writeFileSize - _writeOffset;
367 368 369

    request.hdr.size = _writeSize;

370
    memcpy(request.data, &_writeFileAccumulator.data()[_writeOffset], _writeSize);
371 372 373 374

    _sendRequest(&request);
}

375
void FileManager::receiveMessage(mavlink_message_t message)
Lorenz Meier's avatar
Lorenz Meier committed
376
{
377 378
    // receiveMessage is signalled will all mavlink messages so we need to filter everything else out but ours.
    if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) {
379 380
        return;
    }
381

382 383
    mavlink_file_transfer_protocol_t data;
    mavlink_msg_file_transfer_protocol_decode(&message, &data);
384
	
385 386
    // Make sure we are the target system
    if (data.target_system != _systemIdQGC) {
387
        qDebug() << "Received MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL with incorrect target_system:" <<  data.target_system << "expected:" << _systemIdQGC;
388 389
        return;
    }
390 391
    
    Request* request = (Request*)&data.payload[0];
392 393

    uint16_t incomingSeqNumber = request->hdr.seqNumber;
394
    
395 396 397 398 399 400 401 402 403
    // Make sure we have a good sequence number
    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)) {
        qDebug() << "Received old packet: expected seq:" << expectedSeqNumber << "got:" << incomingSeqNumber;
        return;
    }

404 405
    _clearAckTimeout();
    
406 407
	qCDebug(FileManagerLog) << "receiveMessage" << request->hdr.opcode;
	
408
    if (incomingSeqNumber != expectedSeqNumber) {
409
        bool doAbort = true;
Don Gagne's avatar
Don Gagne committed
410
        switch (_currentOperation) {
411 412 413
            case kCOBurst: // burst download drops are handled in _downloadAckResponse()
                doAbort = false;
                break;
Don Gagne's avatar
Don Gagne committed
414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435
            case kCORead:
                _closeDownloadSession(false /* failure */);
                break;
            
            case kCOWrite:
                _closeUploadSession(false /* failure */);
                break;
                
            case kCOOpenRead:
            case kCOOpenBurst:
            case kCOCreate:
                // We could have an open session hanging around
                _currentOperation = kCOIdle;
                _sendResetCommand();
                break;
                
            default:
                // Don't need to do anything special
                _currentOperation = kCOIdle;
                break;
        }
        
436 437 438 439
        if (doAbort) {
            _emitErrorMessage(tr("Bad sequence number on received message: expected(%1) received(%2)").arg(expectedSeqNumber).arg(incomingSeqNumber));
            return;
        }
440 441 442
    }
    
    // Move past the incoming sequence number for next request
443
    _lastOutgoingRequest.hdr.seqNumber = incomingSeqNumber;
444

445
    if (request->hdr.opcode == kRspAck) {
446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464
        switch (request->hdr.req_opcode) {
			case kCmdListDirectory:
				_listAckResponse(request);
				break;
				
			case kCmdOpenFileRO:
            case kCmdOpenFileWO:
				_openAckResponse(request);
				break;
				
			case kCmdReadFile:
				_downloadAckResponse(request, true /* read file */);
				break;
				
			case kCmdBurstReadFile:
				_downloadAckResponse(request, false /* stream file */);
				break;
				
            case kCmdCreateFile:
465 466
                _createAckResponse(request);
                break;
467 468
                
            case kCmdWriteFile:
469 470
                _writeAckResponse(request);
                break;
471 472 473 474 475 476
                
			default:
				// Ack back from operation which does not require additional work
				_currentOperation = kCOIdle;
				break;
		}
477
    } else if (request->hdr.opcode == kRspNak) {
478
        uint8_t errorCode = request->data[0];
479

480 481 482
        // Nak's normally have 1 byte of data for error code, except for kErrFailErrno which has additional byte for errno
        Q_ASSERT((errorCode == kErrFailErrno && request->hdr.size == 2) || request->hdr.size == 1);
        
483
        _currentOperation = kCOIdle;
484

485 486
        if (request->hdr.req_opcode == kCmdListDirectory && errorCode == kErrEOF) {
            // This is not an error, just the end of the list loop
Don Gagne's avatar
Don Gagne committed
487
            emit commandComplete();
488
            return;
489 490 491
        } else if ((request->hdr.req_opcode == kCmdReadFile || request->hdr.req_opcode == kCmdBurstReadFile) && errorCode == kErrEOF) {
            // This is not an error, just the end of the download loop
            _closeDownloadSession(true /* success */);
492
            return;
493
        } else if (request->hdr.req_opcode == kCmdCreateFile) {
494 495
            _emitErrorMessage(tr("Nak received creating file, error: %1").arg(errorString(request->data[0])));
            return;
496 497 498
        } else if (request->hdr.req_opcode == kCmdCreateDirectory) {
            _emitErrorMessage(tr("Nak received creating directory, error: %1").arg(errorString(request->data[0])));
            return;
499 500
        } else {
            // Generic Nak handling
501 502 503
            if (request->hdr.req_opcode == kCmdReadFile || request->hdr.req_opcode == kCmdBurstReadFile) {
                // Nak error during download loop, download failed
                _closeDownloadSession(false /* failure */);
Don Gagne's avatar
Don Gagne committed
504 505 506
            } else if (request->hdr.req_opcode == kCmdWriteFile) {
                // Nak error during upload loop, upload failed
                _closeUploadSession(false /* failure */);
507 508 509
            }
            _emitErrorMessage(tr("Nak received, error: %1").arg(errorString(request->data[0])));
        }
510 511 512
    } else {
        // Note that we don't change our operation state. If something goes wrong beyond this, the operation
        // will time out.
513
        _emitErrorMessage(tr("Unknown opcode returned from server: %1").arg(request->hdr.opcode));
Lorenz Meier's avatar
Lorenz Meier committed
514 515 516
    }
}

517
void FileManager::listDirectory(const QString& dirPath)
Lorenz Meier's avatar
Lorenz Meier committed
518
{
519 520 521
    if (_currentOperation != kCOIdle) {
        _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
        return;
none's avatar
none committed
522 523
    }

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

none's avatar
none committed
530
    // initialise the lister
531
    _listPath = dirPath;
532 533
    _listOffset = 0;
    _currentOperation = kCOList;
none's avatar
none committed
534 535

    // and send the initial request
536
    _sendListCommand();
none's avatar
none committed
537 538
}

539
void FileManager::_fillRequestWithString(Request* request, const QString& str)
540 541
{
    strncpy((char *)&request->data[0], str.toStdString().c_str(), sizeof(request->data));
Don Gagne's avatar
Don Gagne committed
542
    request->hdr.size = static_cast<uint8_t>(strnlen((const char *)&request->data[0], sizeof(request->data)));
543 544
}

545
void FileManager::_sendListCommand(void)
none's avatar
none committed
546
{
547
    Request request;
none's avatar
none committed
548

549
    request.hdr.session = 0;
550
    request.hdr.opcode = kCmdListDirectory;
551
    request.hdr.offset = _listOffset;
552
    request.hdr.size = 0;
553

554
    _fillRequestWithString(&request, _listPath);
555

556 557
    qCDebug(FileManagerLog) << "listDirectory: path:" << _listPath << "offset:" <<  _listOffset;
    
558
    _sendRequest(&request);
Lorenz Meier's avatar
Lorenz Meier committed
559 560
}

561
void FileManager::downloadPath(const QString& from, const QDir& downloadDir)
Lorenz Meier's avatar
Lorenz Meier committed
562
{
Don Gagne's avatar
Don Gagne committed
563 564 565 566
    if (_currentOperation != kCOIdle) {
        _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
        return;
    }
567 568 569 570 571 572

    _dedicatedLink = _vehicle->priorityLink();
    if (!_dedicatedLink) {
        _emitErrorMessage(tr("Command not sent. No Vehicle links."));
        return;
    }
Don Gagne's avatar
Don Gagne committed
573
    
574 575 576
	qCDebug(FileManagerLog) << "downloadPath from:" << from << "to:" << downloadDir;
	_downloadWorker(from, downloadDir, true /* read file */);
}
577

578 579
void FileManager::streamPath(const QString& from, const QDir& downloadDir)
{
Don Gagne's avatar
Don Gagne committed
580 581 582 583
    if (_currentOperation != kCOIdle) {
        _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
        return;
    }
584 585 586 587 588 589

    _dedicatedLink = _vehicle->priorityLink();
    if (!_dedicatedLink) {
        _emitErrorMessage(tr("Command not sent. No Vehicle links."));
        return;
    }
Don Gagne's avatar
Don Gagne committed
590
    
591 592 593
	qCDebug(FileManagerLog) << "streamPath from:" << from << "to:" << downloadDir;
	_downloadWorker(from, downloadDir, false /* stream file */);
}
Lorenz Meier's avatar
Lorenz Meier committed
594

595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613
void FileManager::_downloadWorker(const QString& from, const QDir& downloadDir, bool readFile)
{
	if (from.isEmpty()) {
		return;
	}
	
	_readFileDownloadDir.setPath(downloadDir.absolutePath());
	
	// 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 i;
	for (i=from.size()-1; i>=0; i--) {
		if (from[i] == '/') {
			break;
		}
	}
	i++; // move past slash
	_readFileDownloadFilename = from.right(from.size() - i);
	
Don Gagne's avatar
Don Gagne committed
614
	_currentOperation = readFile ? kCOOpenRead : kCOOpenBurst;
615 616 617 618 619 620 621 622
	
	Request request;
	request.hdr.session = 0;
	request.hdr.opcode = kCmdOpenFileRO;
	request.hdr.offset = 0;
	request.hdr.size = 0;
	_fillRequestWithString(&request, from);
	_sendRequest(&request);
623
}
none's avatar
none committed
624

625 626 627
/// @brief Uploads the specified file.
///     @param toPath File in UAS to upload to, fully qualified path
///     @param uploadFile Local file to upload from
628
void FileManager::uploadPath(const QString& toPath, const QFileInfo& uploadFile)
629
{
630
    if(_currentOperation != kCOIdle){
631
        _emitErrorMessage(tr("UAS File manager busy. Try again later"));
632 633 634
        return;
    }

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

641 642 643 644
    if (toPath.isEmpty()) {
        return;
    }

Don Gagne's avatar
Don Gagne committed
645
    if (!uploadFile.isReadable()){
646
        _emitErrorMessage(tr("File (%1) is not readable for upload").arg(uploadFile.path()));
Don Gagne's avatar
Don Gagne committed
647
        return;
648 649 650
    }

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

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

659 660 661
    file.close();

    if (_writeFileAccumulator.size() == 0) {
662 663 664 665 666 667 668 669 670 671
        _emitErrorMessage(tr("Unable to read data from local file (%1)").arg(uploadFile.absoluteFilePath()));
        return;
    }

    _currentOperation = kCOCreate;

    Request request;
    request.hdr.session = 0;
    request.hdr.opcode = kCmdCreateFile;
    request.hdr.offset = 0;
672
    request.hdr.size = 0;
673
    _fillRequestWithString(&request, toPath + "/" + uploadFile.fileName());
674 675 676
    _sendRequest(&request);
}

677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694
void FileManager::createDirectory(const QString& directory)
{
    if(_currentOperation != kCOIdle){
        _emitErrorMessage(tr("UAS File manager busy. Try again later"));
        return;
    }

    _currentOperation = kCOCreateDir;

    Request request;
    request.hdr.session = 0;
    request.hdr.opcode = kCmdCreateDirectory;
    request.hdr.offset = 0;
    request.hdr.size = 0;
    _fillRequestWithString(&request, directory);
    _sendRequest(&request);
}

695
QString FileManager::errorString(uint8_t errorCode)
none's avatar
none committed
696 697
{
    switch(errorCode) {
698 699 700 701 702 703 704 705 706 707 708 709 710 711 712
        case kErrNone:
            return QString("no error");
        case kErrFail:
            return QString("unknown error");
        case kErrEOF:
            return QString("read beyond end of file");
        case kErrUnknownCommand:
            return QString("unknown command");
        case kErrFailErrno:
            return QString("command failed");
        case kErrInvalidDataSize:
            return QString("invalid data size");
        case kErrInvalidSession:
            return QString("invalid session");
        case kErrNoSessionsAvailable:
nopeppermint's avatar
nopeppermint committed
713
            return QString("no sessions available");
714 715 716 717
        case kErrFailFileExists:
            return QString("File already exists on target");
        case kErrFailFileProtected:
            return QString("File is write protected");
718 719
        default:
            return QString("unknown error code");
none's avatar
none committed
720 721
    }
}
722 723 724 725 726

/// @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
727
bool FileManager::_sendOpcodeOnlyCmd(uint8_t opcode, OperationState newOpState)
728 729 730 731 732
{
    if (_currentOperation != kCOIdle) {
        // Can't have multiple commands in play at the same time
        return false;
    }
733

734 735 736 737 738
    Request request;
    request.hdr.session = 0;
    request.hdr.opcode = opcode;
    request.hdr.offset = 0;
    request.hdr.size = 0;
739

740
    _currentOperation = newOpState;
741

742
    _sendRequest(&request);
743

744
    return true;
745 746 747
}

/// @brief Starts the ack timeout timer
748
void FileManager::_setupAckTimeout(void)
749
{
750 751
	qCDebug(FileManagerLog) << "_setupAckTimeout";

752
    Q_ASSERT(!_ackTimer.isActive());
753

754 755
    _ackNumTries = 0;
    _ackTimer.setSingleShot(false);
Don Gagne's avatar
Don Gagne committed
756
    _ackTimer.start(ackTimerTimeoutMsecs);
757 758 759
}

/// @brief Clears the ack timeout timer
760
void FileManager::_clearAckTimeout(void)
761
{
762
	qCDebug(FileManagerLog) << "_clearAckTimeout";
763 764 765 766
    _ackTimer.stop();
}

/// @brief Called when ack timeout timer fires
767
void FileManager::_ackTimeout(void)
768
{
769 770
    qCDebug(FileManagerLog) << "_ackTimeout";
    
771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790
    if (++_ackNumTries <= ackTimerMaxRetries) {
        qCDebug(FileManagerLog) << "ack timeout - retrying";
        if (_currentOperation == kCOBurst) {
            // for burst downloads try to initiate a new burst
            Request request;
            request.hdr.session = _activeSession;
            request.hdr.opcode = kCmdBurstReadFile;
            request.hdr.offset = _downloadOffset;
            request.hdr.size = 0;
            request.hdr.seqNumber = ++_lastOutgoingRequest.hdr.seqNumber;

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

    _clearAckTimeout();

Don Gagne's avatar
Don Gagne committed
791 792 793
    // 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.
794 795 796

    switch (_currentOperation) {
        case kCORead:
797 798
        case kCOBurst:
            _closeDownloadSession(false /* failure */);
Don Gagne's avatar
Don Gagne committed
799 800 801 802 803 804 805 806
            _emitErrorMessage(tr("Timeout waiting for ack: Download failed"));
            break;
            
        case kCOOpenRead:
        case kCOOpenBurst:
            _currentOperation = kCOIdle;
            _emitErrorMessage(tr("Timeout waiting for ack: Download failed"));
            _sendResetCommand();
807
            break;
808
            
809
        case kCOCreate:
Don Gagne's avatar
Don Gagne committed
810 811 812
            _currentOperation = kCOIdle;
            _emitErrorMessage(tr("Timeout waiting for ack: Upload failed"));
            _sendResetCommand();
813 814
            break;
            
815
        case kCOWrite:
Don Gagne's avatar
Don Gagne committed
816 817
            _closeUploadSession(false /* failure */);
            _emitErrorMessage(tr("Timeout waiting for ack: Upload failed"));
818
            break;
819
			
820
        default:
821 822
        {
            OperationState currentOperation = _currentOperation;
823
            _currentOperation = kCOIdle;
824 825
            _emitErrorMessage(QString("Timeout waiting for ack: Command failed (%1)").arg(currentOperation));
        }
826 827 828 829
            break;
    }
}

Don Gagne's avatar
Don Gagne committed
830
void FileManager::_sendResetCommand(void)
831 832
{
    Request request;
Don Gagne's avatar
Don Gagne committed
833
    request.hdr.opcode = kCmdResetSessions;
834
    request.hdr.size = 0;
835
    _sendRequest(&request);
836 837
}

838
void FileManager::_emitErrorMessage(const QString& msg)
839
{
840
	qCDebug(FileManagerLog) << "Error:" << msg;
Don Gagne's avatar
Don Gagne committed
841
    emit commandError(msg);
842 843
}

844
void FileManager::_emitListEntry(const QString& entry)
845
{
846
    qCDebug(FileManagerLog) << "_emitListEntry" << entry;
847
    emit listEntry(entry);
848 849
}

850
/// @brief Sends the specified Request out to the UAS.
851
void FileManager::_sendRequest(Request* request)
852
{
853

854
    _setupAckTimeout();
855
    
856 857 858 859 860 861 862
    request->hdr.seqNumber = ++_lastOutgoingRequest.hdr.seqNumber;
    // store the current request
    if (request->hdr.size <= sizeof(request->data)) {
        memcpy(&_lastOutgoingRequest, request, sizeof(RequestHeader) + request->hdr.size);
    } else {
        qCCritical(FileManagerLog) << "request length too long:" << request->hdr.size;
    }
863
    
Don Gagne's avatar
Don Gagne committed
864 865
    qCDebug(FileManagerLog) << "_sendRequest opcode:" << request->hdr.opcode << "seqNumber:" << request->hdr.seqNumber;
    
866
    if (_systemIdQGC == 0) {
867
        _systemIdQGC = qgcApp()->toolbox()->mavlinkProtocol()->getSystemId();
868
    }
869 870 871 872 873 874 875
    _sendRequestNoAck(request);
}

/// @brief Sends the specified Request out to the UAS, without ack timeout handling
void FileManager::_sendRequestNoAck(Request* request)
{
    mavlink_message_t message;
Don Gagne's avatar
Don Gagne committed
876 877 878 879 880 881 882 883

    // Unit testing code can end up here without _dedicateLink set since it tests inidividual commands.
    LinkInterface* link;
    if (_dedicatedLink) {
        link = _dedicatedLink;
    } else {
        link = _vehicle->priorityLink();
    }
884
    
885 886
    mavlink_msg_file_transfer_protocol_pack_chan(_systemIdQGC,       // QGC System ID
                                                 0,                  // QGC Component ID
Don Gagne's avatar
Don Gagne committed
887
                                                 link->mavlinkChannel(),
888 889 890 891 892
                                                 &message,           // Mavlink Message to pack into
                                                 0,                  // Target network
                                                 _systemIdServer,    // Target system
                                                 0,                  // Target component
                                                 (uint8_t*)request); // Payload
893
    
894
    _vehicle->sendMessageOnLinkThreadSafe(link, message);
Lorenz Meier's avatar
Lorenz Meier committed
895
}