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"
Lorenz Meier's avatar
Lorenz Meier committed
29 30 31

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

34
QGC_LOGGING_CATEGORY(FileManagerLog, "FileManagerLog")
35

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

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

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

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

77 78 79
    _sendRequest(&request);
}

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

216 217 218
        cListEntries++;
    }

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

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

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

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

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

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

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

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

273

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

    _writeFileDatablock();
}

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

291 292
    _writeOffset += _writeSize;

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

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

    request.hdr.size = _writeSize;

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

    _sendRequest(&request);
}

310
void FileManager::receiveMessage(LinkInterface* link, mavlink_message_t message)
Lorenz Meier's avatar
Lorenz Meier committed
311
{
312
    Q_UNUSED(link);
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
    }

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

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

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

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

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

470
    _fillRequestWithString(&request, _listPath);
471

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

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

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

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

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

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

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

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

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

557 558 559
    file.close();

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

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

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

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

620
    _currentOperation = newOpState;
621

622
    _sendRequest(&request);
623

624
    return true;
625 626 627
}

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

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

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

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

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

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

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

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

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

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

710
    mavlink_message_t message;
711

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

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