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

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

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

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

78 79 80
    _sendRequest(&request);
}

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

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

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

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

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

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

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

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

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

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

/// @brief Respond to the Ack associated with the List command.
175
void FileManager::_listAckResponse(Request* listAck)
176 177 178 179 180 181
{
    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;
    }
182

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

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

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

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

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

217 218 219
        cListEntries++;
    }

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

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

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

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

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

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

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

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

274

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

    _writeFileDatablock();
}

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

292 293
    _writeOffset += _writeSize;

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

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

    request.hdr.size = _writeSize;

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

    _sendRequest(&request);
}

311
void FileManager::receiveMessage(LinkInterface* link, mavlink_message_t message)
Lorenz Meier's avatar
Lorenz Meier committed
312
{
313
    Q_UNUSED(link);
314

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

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

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

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

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

    // initialise the lister
448
    _listPath = dirPath;
449 450
    _listOffset = 0;
    _currentOperation = kCOList;
none's avatar
none committed
451 452

    // and send the initial request
453
    _sendListCommand();
none's avatar
none committed
454 455
}

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

462
void FileManager::_sendListCommand(void)
none's avatar
none committed
463
{
464
    Request request;
none's avatar
none committed
465

466
    request.hdr.session = 0;
467
    request.hdr.opcode = kCmdListDirectory;
468
    request.hdr.offset = _listOffset;
469
    request.hdr.size = 0;
470

471
    _fillRequestWithString(&request, _listPath);
472

473 474
    qCDebug(FileManagerLog) << "listDirectory: path:" << _listPath << "offset:" <<  _listOffset;
    
475
    _sendRequest(&request);
Lorenz Meier's avatar
Lorenz Meier committed
476 477
}

478
void FileManager::downloadPath(const QString& from, const QDir& downloadDir)
Lorenz Meier's avatar
Lorenz Meier committed
479
{
Don Gagne's avatar
Don Gagne committed
480 481 482 483 484
    if (_currentOperation != kCOIdle) {
        _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
        return;
    }
    
485 486 487
	qCDebug(FileManagerLog) << "downloadPath from:" << from << "to:" << downloadDir;
	_downloadWorker(from, downloadDir, true /* read file */);
}
488

489 490
void FileManager::streamPath(const QString& from, const QDir& downloadDir)
{
Don Gagne's avatar
Don Gagne committed
491 492 493 494 495
    if (_currentOperation != kCOIdle) {
        _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
        return;
    }
    
496 497 498
	qCDebug(FileManagerLog) << "streamPath from:" << from << "to:" << downloadDir;
	_downloadWorker(from, downloadDir, false /* stream file */);
}
Lorenz Meier's avatar
Lorenz Meier committed
499

500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518
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
519
	_currentOperation = readFile ? kCOOpenRead : kCOOpenBurst;
520 521 522 523 524 525 526 527
	
	Request request;
	request.hdr.session = 0;
	request.hdr.opcode = kCmdOpenFileRO;
	request.hdr.offset = 0;
	request.hdr.size = 0;
	_fillRequestWithString(&request, from);
	_sendRequest(&request);
528
}
none's avatar
none committed
529

530 531 532
/// @brief Uploads the specified file.
///     @param toPath File in UAS to upload to, fully qualified path
///     @param uploadFile Local file to upload from
533
void FileManager::uploadPath(const QString& toPath, const QFileInfo& uploadFile)
534
{
535 536 537 538 539
    if(_currentOperation != kCOIdle){
        _emitErrorMessage(tr("UAS File manager busy.  Try again later"));
        return;
    }

540 541 542 543
    if (toPath.isEmpty()) {
        return;
    }

Don Gagne's avatar
Don Gagne committed
544
    if (!uploadFile.isReadable()){
545
        _emitErrorMessage(tr("File (%1) is not readable for upload").arg(uploadFile.path()));
Don Gagne's avatar
Don Gagne committed
546
        return;
547 548 549
    }

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

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

558 559 560
    file.close();

    if (_writeFileAccumulator.size() == 0) {
561 562 563 564 565 566 567 568 569 570
        _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;
571
    request.hdr.size = 0;
572
    _fillRequestWithString(&request, toPath + "/" + uploadFile.fileName());
573 574 575
    _sendRequest(&request);
}

576
QString FileManager::errorString(uint8_t errorCode)
none's avatar
none committed
577 578
{
    switch(errorCode) {
579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594
        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:
            return QString("no sessions availble");
595 596 597 598
        case kErrFailFileExists:
            return QString("File already exists on target");
        case kErrFailFileProtected:
            return QString("File is write protected");
599 600
        default:
            return QString("unknown error code");
none's avatar
none committed
601 602
    }
}
603 604 605 606 607

/// @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
608
bool FileManager::_sendOpcodeOnlyCmd(uint8_t opcode, OperationState newOpState)
609 610 611 612 613
{
    if (_currentOperation != kCOIdle) {
        // Can't have multiple commands in play at the same time
        return false;
    }
614

615 616 617 618 619
    Request request;
    request.hdr.session = 0;
    request.hdr.opcode = opcode;
    request.hdr.offset = 0;
    request.hdr.size = 0;
620

621
    _currentOperation = newOpState;
622

623
    _sendRequest(&request);
624

625
    return true;
626 627 628
}

/// @brief Starts the ack timeout timer
629
void FileManager::_setupAckTimeout(void)
630
{
631 632
	qCDebug(FileManagerLog) << "_setupAckTimeout";

633
    Q_ASSERT(!_ackTimer.isActive());
634

635
    _ackTimer.setSingleShot(true);
Don Gagne's avatar
Don Gagne committed
636
    _ackTimer.start(ackTimerTimeoutMsecs);
637 638 639
}

/// @brief Clears the ack timeout timer
640
void FileManager::_clearAckTimeout(void)
641
{
642
	qCDebug(FileManagerLog) << "_clearAckTimeout";
643 644 645 646
    _ackTimer.stop();
}

/// @brief Called when ack timeout timer fires
647
void FileManager::_ackTimeout(void)
648
{
649 650
    qCDebug(FileManagerLog) << "_ackTimeout";
    
Don Gagne's avatar
Don Gagne committed
651 652 653
    // 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.
654 655 656

    switch (_currentOperation) {
        case kCORead:
657 658
        case kCOBurst:
            _closeDownloadSession(false /* failure */);
Don Gagne's avatar
Don Gagne committed
659 660 661 662 663 664 665 666
            _emitErrorMessage(tr("Timeout waiting for ack: Download failed"));
            break;
            
        case kCOOpenRead:
        case kCOOpenBurst:
            _currentOperation = kCOIdle;
            _emitErrorMessage(tr("Timeout waiting for ack: Download failed"));
            _sendResetCommand();
667
            break;
668
            
669
        case kCOCreate:
Don Gagne's avatar
Don Gagne committed
670 671 672
            _currentOperation = kCOIdle;
            _emitErrorMessage(tr("Timeout waiting for ack: Upload failed"));
            _sendResetCommand();
673 674
            break;
            
675
        case kCOWrite:
Don Gagne's avatar
Don Gagne committed
676 677
            _closeUploadSession(false /* failure */);
            _emitErrorMessage(tr("Timeout waiting for ack: Upload failed"));
678
            break;
679
			
680 681
        default:
            _currentOperation = kCOIdle;
Don Gagne's avatar
Don Gagne committed
682
            _emitErrorMessage(QString("Timeout waiting for ack: Command failed (%1)").arg(_currentOperation));
683 684 685 686
            break;
    }
}

Don Gagne's avatar
Don Gagne committed
687
void FileManager::_sendResetCommand(void)
688 689
{
    Request request;
Don Gagne's avatar
Don Gagne committed
690
    request.hdr.opcode = kCmdResetSessions;
691
    request.hdr.size = 0;
692
    _sendRequest(&request);
693 694
}

695
void FileManager::_emitErrorMessage(const QString& msg)
696
{
697
	qCDebug(FileManagerLog) << "Error:" << msg;
Don Gagne's avatar
Don Gagne committed
698
    emit commandError(msg);
699 700
}

701
void FileManager::_emitListEntry(const QString& entry)
702
{
703
    qCDebug(FileManagerLog) << "_emitListEntry" << entry;
704
    emit listEntry(entry);
705 706
}

707
/// @brief Sends the specified Request out to the UAS.
708
void FileManager::_sendRequest(Request* request)
709
{
710

711
    mavlink_message_t message;
712

713
    _setupAckTimeout();
714 715
    
    _lastOutgoingSeqNumber++;
716

717 718
    request->hdr.seqNumber = _lastOutgoingSeqNumber;
    
Don Gagne's avatar
Don Gagne committed
719 720
    qCDebug(FileManagerLog) << "_sendRequest opcode:" << request->hdr.opcode << "seqNumber:" << request->hdr.seqNumber;
    
721
    if (_systemIdQGC == 0) {
722
        _systemIdQGC = qgcApp()->toolbox()->mavlinkProtocol()->getSystemId();
723 724
    }
    
725
    Q_ASSERT(_vehicle);
726 727 728 729 730 731 732 733
    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
    
734
    _vehicle->sendMessage(message);
Lorenz Meier's avatar
Lorenz Meier committed
735
}