FileManager.cc 24.5 KB
Newer Older
1
/*=====================================================================
2

3
 QGroundControl Open Source Ground Control Station
4

5
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
6

7
 This file is part of the QGROUNDCONTROL project
8

9 10 11 12
 QGROUNDCONTROL is free software: you can redistribute it and/or modify
 it under the terms of the GNU General Public License as published by
 the Free Software Foundation, either version 3 of the License, or
 (at your option) any later version.
13

14 15 16 17
 QGROUNDCONTROL is distributed in the hope that it will be useful,
 but WITHOUT ANY WARRANTY; without even the implied warranty of
 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 GNU General Public License for more details.
18

19 20
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
21

22 23
 ======================================================================*/

24
#include "FileManager.h"
25
#include "QGC.h"
Lorenz Meier's avatar
Lorenz Meier committed
26
#include "MAVLinkProtocol.h"
27
#include "MainWindow.h"
28
#include "Vehicle.h"
29
#include "QGCApplication.h"
Lorenz Meier's avatar
Lorenz Meier committed
30 31 32

#include <QFile>
#include <QDir>
none's avatar
none committed
33
#include <string>
Lorenz Meier's avatar
Lorenz Meier committed
34

35
QGC_LOGGING_CATEGORY(FileManagerLog, "FileManagerLog")
36

37 38 39 40 41 42 43 44
FileManager::FileManager(QObject* parent, Vehicle* vehicle)
    : QObject(parent)
    , _currentOperation(kCOIdle)
    , _vehicle(vehicle)
    , _dedicatedLink(NULL)
    , _lastOutgoingSeqNumber(0)
    , _activeSession(0)
    , _systemIdQGC(0)
Lorenz Meier's avatar
Lorenz Meier committed
45
{
46
    connect(&_ackTimer, &QTimer::timeout, this, &FileManager::_ackTimeout);
47
    
48
    _systemIdServer = _vehicle->id();
49 50
    
    // Make sure we don't have bad structure packing
51
    Q_ASSERT(sizeof(RequestHeader) == 12);
Lorenz Meier's avatar
Lorenz Meier committed
52 53
}

Don Gagne's avatar
Don Gagne committed
54
/// Respond to the Ack associated with the Open command with the next read command.
55
void FileManager::_openAckResponse(Request* openAck)
56
{
Don Gagne's avatar
Don Gagne committed
57 58 59
    qCDebug(FileManagerLog) << QString("_openAckResponse: _currentOperation(%1) _readFileLength(%2)").arg(_currentOperation).arg(openAck->openFileLength);
    
	Q_ASSERT(_currentOperation == kCOOpenRead || _currentOperation == kCOOpenBurst);
60
	_currentOperation = _currentOperation == kCOOpenRead ? kCORead : kCOBurst;
61
    _activeSession = openAck->hdr.session;
62 63 64
    
    // File length comes back in data
    Q_ASSERT(openAck->hdr.size == sizeof(uint32_t));
Don Gagne's avatar
Don Gagne committed
65
    _downloadFileSize = openAck->openFileLength;
66 67
    
    // Start the sequence of read commands
68

Don Gagne's avatar
Don Gagne committed
69
    _downloadOffset = 0;            // Start reading at beginning of file
70
    _readFileAccumulator.clear();   // Start with an empty file
71

72 73
    Request request;
    request.hdr.session = _activeSession;
74 75 76
	Q_ASSERT(_currentOperation == kCORead || _currentOperation == kCOBurst);
	request.hdr.opcode = _currentOperation == kCORead ? kCmdReadFile : kCmdBurstReadFile;
    request.hdr.offset = _downloadOffset;
77
    request.hdr.size = sizeof(request.data);
78

79 80 81
    _sendRequest(&request);
}

Don Gagne's avatar
Don Gagne committed
82
/// Closes out a download session by writing the file and doing cleanup.
83
///     @param success true: successful download completion, false: error during download
84
void FileManager::_closeDownloadSession(bool success)
85
{
Don Gagne's avatar
Don Gagne committed
86 87 88 89
    qCDebug(FileManagerLog) << QString("_closeDownloadSession: success(%1)").arg(success);
    
    _currentOperation = kCOIdle;
    
90 91
    if (success) {
        QString downloadFilePath = _readFileDownloadDir.absoluteFilePath(_readFileDownloadFilename);
92

93 94 95 96 97
        QFile file(downloadFilePath);
        if (!file.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
            _emitErrorMessage(tr("Unable to open local file for writing (%1)").arg(downloadFilePath));
            return;
        }
98

99 100 101 102 103 104 105
        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();
106

Don Gagne's avatar
Don Gagne committed
107
        emit commandComplete();
108
    }
Don Gagne's avatar
Don Gagne committed
109
    
Don Gagne's avatar
Don Gagne committed
110 111
    _readFileAccumulator.clear();
    
112
    // Close the open session
Don Gagne's avatar
Don Gagne committed
113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131
    _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();
132 133
}

134 135 136
/// 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)
137 138
{
    if (readAck->hdr.session != _activeSession) {
Don Gagne's avatar
Don Gagne committed
139
        _closeDownloadSession(false /* failure */);
140
        _emitErrorMessage(tr("Download: Incorrect session returned"));
141 142
        return;
    }
143

144
    if (readAck->hdr.offset != _downloadOffset) {
Don Gagne's avatar
Don Gagne committed
145
        _closeDownloadSession(false /* failure */);
146
        _emitErrorMessage(tr("Download: Offset returned (%1) differs from offset requested/expected (%2)").arg(readAck->hdr.offset).arg(_downloadOffset));
147 148
        return;
    }
149 150
    
    qCDebug(FileManagerLog) << QString("_downloadAckResponse: offset(%1) size(%2) burstComplete(%3)").arg(readAck->hdr.offset).arg(readAck->hdr.size).arg(readAck->hdr.burstComplete);
151

152
	_downloadOffset += readAck->hdr.size;
153
    _readFileAccumulator.append((const char*)readAck->data, readAck->hdr.size);
Don Gagne's avatar
Don Gagne committed
154 155 156 157
    
    if (_downloadFileSize != 0) {
        emit commandProgress(100 * ((float)_readFileAccumulator.length() / (float)_downloadFileSize));
    }
158

Don Gagne's avatar
Don Gagne committed
159 160
    if (readFile || readAck->hdr.burstComplete) {
        // Possibly still more data to read, send next read request
161

Don Gagne's avatar
Don Gagne committed
162 163 164 165 166
        Request request;
        request.hdr.session = _activeSession;
        request.hdr.opcode = readFile ? kCmdReadFile : kCmdBurstReadFile;
        request.hdr.offset = _downloadOffset;
        request.hdr.size = 0;
167

Don Gagne's avatar
Don Gagne committed
168 169 170 171
        _sendRequest(&request);
    } else if (!readFile) {
        // Streaming, so next ack should come automatically
        _setupAckTimeout();
172 173 174 175
    }
}

/// @brief Respond to the Ack associated with the List command.
176
void FileManager::_listAckResponse(Request* listAck)
177 178 179 180 181 182
{
    if (listAck->hdr.offset != _listOffset) {
        _currentOperation = kCOIdle;
        _emitErrorMessage(tr("List: Offset returned (%1) differs from offset requested (%2)").arg(listAck->hdr.offset).arg(_listOffset));
        return;
    }
183

184 185 186
    uint8_t offset = 0;
    uint8_t cListEntries = 0;
    uint8_t cBytes = listAck->hdr.size;
187

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

192 193
        // get the length of the name
        uint8_t cBytesLeft = cBytes - offset;
Don Gagne's avatar
Don Gagne committed
194
        uint8_t nlen = static_cast<uint8_t>(strnlen(ptr, cBytesLeft));
195
        if ((*ptr == 'S' && nlen > 1) || (*ptr != 'S' && nlen < 2)) {
196 197 198 199 200 201 202 203
            _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;
        }
204

205
        // Returned names are prepended with D for directory, F for file, S for skip
206 207
        if (*ptr == 'F' || *ptr == 'D') {
            // put it in the view
208
            _emitListEntry(ptr);
209 210
        } else if (*ptr == 'S') {
            // do nothing
211 212
        } else {
            qDebug() << "unknown entry" << ptr;
213
        }
214

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

218 219 220
        cListEntries++;
    }

Don Gagne's avatar
Don Gagne committed
221
    if (listAck->hdr.size == 0 || cListEntries == 0) {
222 223 224
        // Directory is empty, we're done
        Q_ASSERT(listAck->hdr.opcode == kRspAck);
        _currentOperation = kCOIdle;
Don Gagne's avatar
Don Gagne committed
225
        emit commandComplete();
226 227
    } else {
        // Possibly more entries to come, need to keep trying till we get EOF
228 229 230
        _currentOperation = kCOList;
        _listOffset += cListEntries;
        _sendListCommand();
231 232 233
    }
}

234
/// @brief Respond to the Ack associated with the create command.
235
void FileManager::_createAckResponse(Request* createAck)
236
{
Don Gagne's avatar
Don Gagne committed
237 238
    qCDebug(FileManagerLog) << "_createAckResponse";
    
239 240 241
    _currentOperation = kCOWrite;
    _activeSession = createAck->hdr.session;

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

Don Gagne's avatar
Don Gagne committed
244
    _writeOffset = 0;
245
    _writeSize = 0;
Don Gagne's avatar
Don Gagne committed
246
    
247 248 249 250
    _writeFileDatablock();
}

/// @brief Respond to the Ack associated with the write command.
251
void FileManager::_writeAckResponse(Request* writeAck)
252
{
253
    if(_writeOffset + _writeSize >= _writeFileSize){
Don Gagne's avatar
Don Gagne committed
254
        _closeUploadSession(true /* success */);
255 256
    }

257
    if (writeAck->hdr.session != _activeSession) {
Don Gagne's avatar
Don Gagne committed
258
        _closeUploadSession(false /* failure */);
259 260 261 262 263
        _emitErrorMessage(tr("Write: Incorrect session returned"));
        return;
    }

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

269
    if (writeAck->hdr.size != sizeof(uint32_t)) {
Don Gagne's avatar
Don Gagne committed
270
        _closeUploadSession(false /* failure */);
271
        _emitErrorMessage(tr("Write: Returned invalid size of write size data"));
272 273 274
        return;
    }

275

Don Gagne's avatar
Don Gagne committed
276 277
    if( writeAck->writeFileLength !=_writeSize) {
        _closeUploadSession(false /* failure */);
278
        _emitErrorMessage(tr("Write: Size returned (%1) differs from size requested (%2)").arg(writeAck->writeFileLength).arg(_writeSize));
279 280 281 282 283 284 285
        return;
    }

    _writeFileDatablock();
}

/// @brief Send next write file data block.
286
void FileManager::_writeFileDatablock(void)
287
{
Don Gagne's avatar
Don Gagne committed
288 289
    if (_writeOffset + _writeSize >= _writeFileSize){
        _closeUploadSession(true /* success */);
290
        return;
291 292
    }

293 294
    _writeOffset += _writeSize;

295 296 297 298 299
    Request request;
    request.hdr.session = _activeSession;
    request.hdr.opcode = kCmdWriteFile;
    request.hdr.offset = _writeOffset;

300
    if(_writeFileSize -_writeOffset > sizeof(request.data) )
301 302
        _writeSize = sizeof(request.data);
    else
303
        _writeSize = _writeFileSize - _writeOffset;
304 305 306

    request.hdr.size = _writeSize;

307
    memcpy(request.data, &_writeFileAccumulator.data()[_writeOffset], _writeSize);
308 309 310 311

    _sendRequest(&request);
}

312
void FileManager::receiveMessage(mavlink_message_t message)
Lorenz Meier's avatar
Lorenz Meier committed
313
{
314 315
    // 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) {
316 317
        return;
    }
318
	
319 320
    mavlink_file_transfer_protocol_t data;
    mavlink_msg_file_transfer_protocol_decode(&message, &data);
321
	
322 323
    // Make sure we are the target system
    if (data.target_system != _systemIdQGC) {
324
        qDebug() << "Received MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL with incorrect target_system:" <<  data.target_system << "expected:" << _systemIdQGC;
325 326
        return;
    }
327 328 329
    
    Request* request = (Request*)&data.payload[0];
    
330 331
    _clearAckTimeout();
    
332 333
	qCDebug(FileManagerLog) << "receiveMessage" << request->hdr.opcode;
	
334
    uint16_t incomingSeqNumber = request->hdr.seqNumber;
335 336 337 338
    
    // Make sure we have a good sequence number
    uint16_t expectedSeqNumber = _lastOutgoingSeqNumber + 1;
    if (incomingSeqNumber != expectedSeqNumber) {
Don Gagne's avatar
Don Gagne committed
339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362
        switch (_currentOperation) {
            case kCOBurst:
            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;
        }
        
363 364 365 366 367 368
        _emitErrorMessage(tr("Bad sequence number on received message: expected(%1) received(%2)").arg(expectedSeqNumber).arg(incomingSeqNumber));
        return;
    }
    
    // Move past the incoming sequence number for next request
    _lastOutgoingSeqNumber = incomingSeqNumber;
369

370
    if (request->hdr.opcode == kRspAck) {
371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389
        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:
390 391
                _createAckResponse(request);
                break;
392 393
                
            case kCmdWriteFile:
394 395
                _writeAckResponse(request);
                break;
396 397 398 399 400 401
                
			default:
				// Ack back from operation which does not require additional work
				_currentOperation = kCOIdle;
				break;
		}
402
    } else if (request->hdr.opcode == kRspNak) {
403
        uint8_t errorCode = request->data[0];
404

405 406 407
        // 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);
        
408
        _currentOperation = kCOIdle;
409

410 411
        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
412
            emit commandComplete();
413
            return;
414 415 416
        } 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 */);
417
            return;
418
        } else if (request->hdr.req_opcode == kCmdCreateFile) {
419 420
            _emitErrorMessage(tr("Nak received creating file, error: %1").arg(errorString(request->data[0])));
            return;
421 422
        } else {
            // Generic Nak handling
423 424 425
            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
426 427 428
            } else if (request->hdr.req_opcode == kCmdWriteFile) {
                // Nak error during upload loop, upload failed
                _closeUploadSession(false /* failure */);
429 430 431
            }
            _emitErrorMessage(tr("Nak received, error: %1").arg(errorString(request->data[0])));
        }
432 433 434
    } else {
        // Note that we don't change our operation state. If something goes wrong beyond this, the operation
        // will time out.
435
        _emitErrorMessage(tr("Unknown opcode returned from server: %1").arg(request->hdr.opcode));
Lorenz Meier's avatar
Lorenz Meier committed
436 437 438
    }
}

439
void FileManager::listDirectory(const QString& dirPath)
Lorenz Meier's avatar
Lorenz Meier committed
440
{
441 442 443
    if (_currentOperation != kCOIdle) {
        _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
        return;
none's avatar
none committed
444 445
    }

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

none's avatar
none committed
452
    // initialise the lister
453
    _listPath = dirPath;
454 455
    _listOffset = 0;
    _currentOperation = kCOList;
none's avatar
none committed
456 457

    // and send the initial request
458
    _sendListCommand();
none's avatar
none committed
459 460
}

461
void FileManager::_fillRequestWithString(Request* request, const QString& str)
462 463
{
    strncpy((char *)&request->data[0], str.toStdString().c_str(), sizeof(request->data));
Don Gagne's avatar
Don Gagne committed
464
    request->hdr.size = static_cast<uint8_t>(strnlen((const char *)&request->data[0], sizeof(request->data)));
465 466
}

467
void FileManager::_sendListCommand(void)
none's avatar
none committed
468
{
469
    Request request;
none's avatar
none committed
470

471
    request.hdr.session = 0;
472
    request.hdr.opcode = kCmdListDirectory;
473
    request.hdr.offset = _listOffset;
474
    request.hdr.size = 0;
475

476
    _fillRequestWithString(&request, _listPath);
477

478 479
    qCDebug(FileManagerLog) << "listDirectory: path:" << _listPath << "offset:" <<  _listOffset;
    
480
    _sendRequest(&request);
Lorenz Meier's avatar
Lorenz Meier committed
481 482
}

483
void FileManager::downloadPath(const QString& from, const QDir& downloadDir)
Lorenz Meier's avatar
Lorenz Meier committed
484
{
Don Gagne's avatar
Don Gagne committed
485 486 487 488
    if (_currentOperation != kCOIdle) {
        _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
        return;
    }
489 490 491 492 493 494

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

500 501
void FileManager::streamPath(const QString& from, const QDir& downloadDir)
{
Don Gagne's avatar
Don Gagne committed
502 503 504 505
    if (_currentOperation != kCOIdle) {
        _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
        return;
    }
506 507 508 509 510 511

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

517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535
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
536
	_currentOperation = readFile ? kCOOpenRead : kCOOpenBurst;
537 538 539 540 541 542 543 544
	
	Request request;
	request.hdr.session = 0;
	request.hdr.opcode = kCmdOpenFileRO;
	request.hdr.offset = 0;
	request.hdr.size = 0;
	_fillRequestWithString(&request, from);
	_sendRequest(&request);
545
}
none's avatar
none committed
546

547 548 549
/// @brief Uploads the specified file.
///     @param toPath File in UAS to upload to, fully qualified path
///     @param uploadFile Local file to upload from
550
void FileManager::uploadPath(const QString& toPath, const QFileInfo& uploadFile)
551
{
552 553 554 555 556
    if(_currentOperation != kCOIdle){
        _emitErrorMessage(tr("UAS File manager busy.  Try again later"));
        return;
    }

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

563 564 565 566
    if (toPath.isEmpty()) {
        return;
    }

Don Gagne's avatar
Don Gagne committed
567
    if (!uploadFile.isReadable()){
568
        _emitErrorMessage(tr("File (%1) is not readable for upload").arg(uploadFile.path()));
Don Gagne's avatar
Don Gagne committed
569
        return;
570 571 572
    }

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

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

581 582 583
    file.close();

    if (_writeFileAccumulator.size() == 0) {
584 585 586 587 588 589 590 591 592 593
        _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;
594
    request.hdr.size = 0;
595
    _fillRequestWithString(&request, toPath + "/" + uploadFile.fileName());
596 597 598
    _sendRequest(&request);
}

599
QString FileManager::errorString(uint8_t errorCode)
none's avatar
none committed
600 601
{
    switch(errorCode) {
602 603 604 605 606 607 608 609 610 611 612 613 614 615 616
        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
617
            return QString("no sessions available");
618 619 620 621
        case kErrFailFileExists:
            return QString("File already exists on target");
        case kErrFailFileProtected:
            return QString("File is write protected");
622 623
        default:
            return QString("unknown error code");
none's avatar
none committed
624 625
    }
}
626 627 628 629 630

/// @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
631
bool FileManager::_sendOpcodeOnlyCmd(uint8_t opcode, OperationState newOpState)
632 633 634 635 636
{
    if (_currentOperation != kCOIdle) {
        // Can't have multiple commands in play at the same time
        return false;
    }
637

638 639 640 641 642
    Request request;
    request.hdr.session = 0;
    request.hdr.opcode = opcode;
    request.hdr.offset = 0;
    request.hdr.size = 0;
643

644
    _currentOperation = newOpState;
645

646
    _sendRequest(&request);
647

648
    return true;
649 650 651
}

/// @brief Starts the ack timeout timer
652
void FileManager::_setupAckTimeout(void)
653
{
654 655
	qCDebug(FileManagerLog) << "_setupAckTimeout";

656
    Q_ASSERT(!_ackTimer.isActive());
657

658
    _ackTimer.setSingleShot(true);
Don Gagne's avatar
Don Gagne committed
659
    _ackTimer.start(ackTimerTimeoutMsecs);
660 661 662
}

/// @brief Clears the ack timeout timer
663
void FileManager::_clearAckTimeout(void)
664
{
665
	qCDebug(FileManagerLog) << "_clearAckTimeout";
666 667 668 669
    _ackTimer.stop();
}

/// @brief Called when ack timeout timer fires
670
void FileManager::_ackTimeout(void)
671
{
672 673
    qCDebug(FileManagerLog) << "_ackTimeout";
    
Don Gagne's avatar
Don Gagne committed
674 675 676
    // 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.
677 678 679

    switch (_currentOperation) {
        case kCORead:
680 681
        case kCOBurst:
            _closeDownloadSession(false /* failure */);
Don Gagne's avatar
Don Gagne committed
682 683 684 685 686 687 688 689
            _emitErrorMessage(tr("Timeout waiting for ack: Download failed"));
            break;
            
        case kCOOpenRead:
        case kCOOpenBurst:
            _currentOperation = kCOIdle;
            _emitErrorMessage(tr("Timeout waiting for ack: Download failed"));
            _sendResetCommand();
690
            break;
691
            
692
        case kCOCreate:
Don Gagne's avatar
Don Gagne committed
693 694 695
            _currentOperation = kCOIdle;
            _emitErrorMessage(tr("Timeout waiting for ack: Upload failed"));
            _sendResetCommand();
696 697
            break;
            
698
        case kCOWrite:
Don Gagne's avatar
Don Gagne committed
699 700
            _closeUploadSession(false /* failure */);
            _emitErrorMessage(tr("Timeout waiting for ack: Upload failed"));
701
            break;
702
			
703 704
        default:
            _currentOperation = kCOIdle;
Don Gagne's avatar
Don Gagne committed
705
            _emitErrorMessage(QString("Timeout waiting for ack: Command failed (%1)").arg(_currentOperation));
706 707 708 709
            break;
    }
}

Don Gagne's avatar
Don Gagne committed
710
void FileManager::_sendResetCommand(void)
711 712
{
    Request request;
Don Gagne's avatar
Don Gagne committed
713
    request.hdr.opcode = kCmdResetSessions;
714
    request.hdr.size = 0;
715
    _sendRequest(&request);
716 717
}

718
void FileManager::_emitErrorMessage(const QString& msg)
719
{
720
	qCDebug(FileManagerLog) << "Error:" << msg;
Don Gagne's avatar
Don Gagne committed
721
    emit commandError(msg);
722 723
}

724
void FileManager::_emitListEntry(const QString& entry)
725
{
726
    qCDebug(FileManagerLog) << "_emitListEntry" << entry;
727
    emit listEntry(entry);
728 729
}

730
/// @brief Sends the specified Request out to the UAS.
731
void FileManager::_sendRequest(Request* request)
732
{
733

734
    mavlink_message_t message;
735

736
    _setupAckTimeout();
737 738
    
    _lastOutgoingSeqNumber++;
739

740 741
    request->hdr.seqNumber = _lastOutgoingSeqNumber;
    
Don Gagne's avatar
Don Gagne committed
742 743
    qCDebug(FileManagerLog) << "_sendRequest opcode:" << request->hdr.opcode << "seqNumber:" << request->hdr.seqNumber;
    
744
    if (_systemIdQGC == 0) {
745
        _systemIdQGC = qgcApp()->toolbox()->mavlinkProtocol()->getSystemId();
746 747
    }
    
748
    Q_ASSERT(_vehicle);
749 750 751 752 753 754 755 756
    mavlink_msg_file_transfer_protocol_pack(_systemIdQGC,       // QGC System ID
                                            0,                  // QGC Component ID
                                            &message,           // Mavlink Message to pack into
                                            0,                  // Target network
                                            _systemIdServer,    // Target system
                                            0,                  // Target component
                                            (uint8_t*)request); // Payload
    
757
    _vehicle->sendMessageOnLink(_dedicatedLink, message);
Lorenz Meier's avatar
Lorenz Meier committed
758
}