FileManager.cc 29.9 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 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.
 *
 ****************************************************************************/
9

10

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

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

22
QGC_LOGGING_CATEGORY(FileManagerLog, "FileManagerLog")
23

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

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

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

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

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

72 73 74
    _sendRequest(&request);
}

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 105
/// 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
106
/// Closes out a download session by writing the file and doing cleanup.
107
///     @param success true: successful download completion, false: error during download
108
void FileManager::_closeDownloadSession(bool success)
109
{
110
    qCDebug(FileManagerLog) << QString("_closeDownloadSession: success(%1) missingBytes(%2)").arg(success).arg(_missingDownloadedBytes);
Don Gagne's avatar
Don Gagne committed
111 112 113
    
    _currentOperation = kCOIdle;
    
114
    if (success) {
115 116 117 118 119 120 121 122
        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;
        }

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

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

131 132 133 134 135 136 137
        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();
138

Don Gagne's avatar
Don Gagne committed
139
        emit commandComplete();
140
    }
Don Gagne's avatar
Don Gagne committed
141
    
Don Gagne's avatar
Don Gagne committed
142 143
    _readFileAccumulator.clear();
    
144
    // Close the open session
Don Gagne's avatar
Don Gagne committed
145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163
    _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();
164 165
}

166 167 168
/// 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)
169 170
{
    if (readAck->hdr.session != _activeSession) {
Don Gagne's avatar
Don Gagne committed
171
        _closeDownloadSession(false /* failure */);
172
        _emitErrorMessage(tr("Download: Incorrect session returned"));
173 174
        return;
    }
175

176
    if (readAck->hdr.offset != _downloadOffset) {
177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195
        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
        }
196
    }
197 198
    
    qCDebug(FileManagerLog) << QString("_downloadAckResponse: offset(%1) size(%2) burstComplete(%3)").arg(readAck->hdr.offset).arg(readAck->hdr.size).arg(readAck->hdr.burstComplete);
199

200 201 202 203 204 205 206 207 208 209 210 211 212 213
    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
214 215
    
    if (_downloadFileSize != 0) {
216
        emit commandProgress(100 * ((float)(_readFileAccumulator.length() - _missingDownloadedBytes) / (float)_downloadFileSize));
Don Gagne's avatar
Don Gagne committed
217
    }
218

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

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

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

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

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

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

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

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

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

281 282 283
        cListEntries++;
    }

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

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

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

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

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

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

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

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

339

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

    _writeFileDatablock();
}

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

357 358
    _writeOffset += _writeSize;

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

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

    request.hdr.size = _writeSize;

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

    _sendRequest(&request);
}

376
void FileManager::receiveMessage(mavlink_message_t message)
Lorenz Meier's avatar
Lorenz Meier committed
377
{
378 379
    // 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) {
380 381
        return;
    }
382

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

    uint16_t incomingSeqNumber = request->hdr.seqNumber;
395
    
396 397 398 399 400 401 402 403 404
    // 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;
    }

405 406
    _clearAckTimeout();
    
407 408
	qCDebug(FileManagerLog) << "receiveMessage" << request->hdr.opcode;
	
409
    if (incomingSeqNumber != expectedSeqNumber) {
410
        bool doAbort = true;
Don Gagne's avatar
Don Gagne committed
411
        switch (_currentOperation) {
412 413 414
            case kCOBurst: // burst download drops are handled in _downloadAckResponse()
                doAbort = false;
                break;
Don Gagne's avatar
Don Gagne committed
415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436
            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;
        }
        
437 438 439 440
        if (doAbort) {
            _emitErrorMessage(tr("Bad sequence number on received message: expected(%1) received(%2)").arg(expectedSeqNumber).arg(incomingSeqNumber));
            return;
        }
441 442 443
    }
    
    // Move past the incoming sequence number for next request
444
    _lastOutgoingRequest.hdr.seqNumber = incomingSeqNumber;
445

446
    if (request->hdr.opcode == kRspAck) {
447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465
        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:
466 467
                _createAckResponse(request);
                break;
468 469
                
            case kCmdWriteFile:
470 471
                _writeAckResponse(request);
                break;
472 473 474 475 476 477
                
			default:
				// Ack back from operation which does not require additional work
				_currentOperation = kCOIdle;
				break;
		}
478
    } else if (request->hdr.opcode == kRspNak) {
479
        uint8_t errorCode = request->data[0];
480

481 482 483
        // 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);
        
484
        _currentOperation = kCOIdle;
485

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

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

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

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

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

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

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

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

555
    _fillRequestWithString(&request, _listPath);
556

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

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

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

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

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

596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614
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
615
	_currentOperation = readFile ? kCOOpenRead : kCOOpenBurst;
616 617 618 619 620 621 622 623
	
	Request request;
	request.hdr.session = 0;
	request.hdr.opcode = kCmdOpenFileRO;
	request.hdr.offset = 0;
	request.hdr.size = 0;
	_fillRequestWithString(&request, from);
	_sendRequest(&request);
624
}
none's avatar
none committed
625

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

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

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

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

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

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

660 661 662
    file.close();

    if (_writeFileAccumulator.size() == 0) {
663 664 665 666 667 668 669 670 671 672
        _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;
673
    request.hdr.size = 0;
674
    _fillRequestWithString(&request, toPath + "/" + uploadFile.fileName());
675 676 677
    _sendRequest(&request);
}

678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695
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);
}

696
QString FileManager::errorString(uint8_t errorCode)
none's avatar
none committed
697 698
{
    switch(errorCode) {
699 700 701 702 703 704 705 706 707 708 709 710 711 712 713
        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
714
            return QString("no sessions available");
715 716 717 718
        case kErrFailFileExists:
            return QString("File already exists on target");
        case kErrFailFileProtected:
            return QString("File is write protected");
719 720
        default:
            return QString("unknown error code");
none's avatar
none committed
721 722
    }
}
723 724 725 726 727

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

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

741
    _currentOperation = newOpState;
742

743
    _sendRequest(&request);
744

745
    return true;
746 747 748
}

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

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

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

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

/// @brief Called when ack timeout timer fires
768
void FileManager::_ackTimeout(void)
769
{
770 771
    qCDebug(FileManagerLog) << "_ackTimeout";
    
772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791
    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
792 793 794
    // 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.
795 796 797

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

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

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

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

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

855
    _setupAckTimeout();
856
    
857 858 859 860 861 862 863
    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;
    }
864
    
Don Gagne's avatar
Don Gagne committed
865 866
    qCDebug(FileManagerLog) << "_sendRequest opcode:" << request->hdr.opcode << "seqNumber:" << request->hdr.seqNumber;
    
867
    if (_systemIdQGC == 0) {
868
        _systemIdQGC = qgcApp()->toolbox()->mavlinkProtocol()->getSystemId();
869
    }
870 871 872 873 874 875 876
    _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
877 878 879 880 881 882 883 884

    // 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();
    }
885
    
886 887
    mavlink_msg_file_transfer_protocol_pack_chan(_systemIdQGC,       // QGC System ID
                                                 0,                  // QGC Component ID
Don Gagne's avatar
Don Gagne committed
888
                                                 link->mavlinkChannel(),
889 890 891 892 893
                                                 &message,           // Mavlink Message to pack into
                                                 0,                  // Target network
                                                 _systemIdServer,    // Target system
                                                 0,                  // Target component
                                                 (uint8_t*)request); // Payload
894
    
Don Gagne's avatar
Don Gagne committed
895
    _vehicle->sendMessageOnLink(link, message);
Lorenz Meier's avatar
Lorenz Meier committed
896
}