FileManager.cc 24.2 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 30 31
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
32
{
33
    connect(&_ackTimer, &QTimer::timeout, this, &FileManager::_ackTimeout);
34
    
35
    _systemIdServer = _vehicle->id();
36 37
    
    // Make sure we don't have bad structure packing
38
    Q_ASSERT(sizeof(RequestHeader) == 12);
Lorenz Meier's avatar
Lorenz Meier committed
39 40
}

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

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

59 60
    Request request;
    request.hdr.session = _activeSession;
61 62 63
	Q_ASSERT(_currentOperation == kCORead || _currentOperation == kCOBurst);
	request.hdr.opcode = _currentOperation == kCORead ? kCmdReadFile : kCmdBurstReadFile;
    request.hdr.offset = _downloadOffset;
64
    request.hdr.size = sizeof(request.data);
65

66 67 68
    _sendRequest(&request);
}

Don Gagne's avatar
Don Gagne committed
69
/// Closes out a download session by writing the file and doing cleanup.
70
///     @param success true: successful download completion, false: error during download
71
void FileManager::_closeDownloadSession(bool success)
72
{
Don Gagne's avatar
Don Gagne committed
73 74 75 76
    qCDebug(FileManagerLog) << QString("_closeDownloadSession: success(%1)").arg(success);
    
    _currentOperation = kCOIdle;
    
77 78
    if (success) {
        QString downloadFilePath = _readFileDownloadDir.absoluteFilePath(_readFileDownloadFilename);
79

80 81 82 83 84
        QFile file(downloadFilePath);
        if (!file.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
            _emitErrorMessage(tr("Unable to open local file for writing (%1)").arg(downloadFilePath));
            return;
        }
85

86 87 88 89 90 91 92
        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();
93

Don Gagne's avatar
Don Gagne committed
94
        emit commandComplete();
95
    }
Don Gagne's avatar
Don Gagne committed
96
    
Don Gagne's avatar
Don Gagne committed
97 98
    _readFileAccumulator.clear();
    
99
    // Close the open session
Don Gagne's avatar
Don Gagne committed
100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118
    _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();
119 120
}

121 122 123
/// 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)
124 125
{
    if (readAck->hdr.session != _activeSession) {
Don Gagne's avatar
Don Gagne committed
126
        _closeDownloadSession(false /* failure */);
127
        _emitErrorMessage(tr("Download: Incorrect session returned"));
128 129
        return;
    }
130

131
    if (readAck->hdr.offset != _downloadOffset) {
Don Gagne's avatar
Don Gagne committed
132
        _closeDownloadSession(false /* failure */);
133
        _emitErrorMessage(tr("Download: Offset returned (%1) differs from offset requested/expected (%2)").arg(readAck->hdr.offset).arg(_downloadOffset));
134 135
        return;
    }
136 137
    
    qCDebug(FileManagerLog) << QString("_downloadAckResponse: offset(%1) size(%2) burstComplete(%3)").arg(readAck->hdr.offset).arg(readAck->hdr.size).arg(readAck->hdr.burstComplete);
138

139
	_downloadOffset += readAck->hdr.size;
140
    _readFileAccumulator.append((const char*)readAck->data, readAck->hdr.size);
Don Gagne's avatar
Don Gagne committed
141 142 143 144
    
    if (_downloadFileSize != 0) {
        emit commandProgress(100 * ((float)_readFileAccumulator.length() / (float)_downloadFileSize));
    }
145

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

Don Gagne's avatar
Don Gagne committed
149 150 151 152 153
        Request request;
        request.hdr.session = _activeSession;
        request.hdr.opcode = readFile ? kCmdReadFile : kCmdBurstReadFile;
        request.hdr.offset = _downloadOffset;
        request.hdr.size = 0;
154

Don Gagne's avatar
Don Gagne committed
155 156 157 158
        _sendRequest(&request);
    } else if (!readFile) {
        // Streaming, so next ack should come automatically
        _setupAckTimeout();
159 160 161 162
    }
}

/// @brief Respond to the Ack associated with the List command.
163
void FileManager::_listAckResponse(Request* listAck)
164 165 166 167 168 169
{
    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;
    }
170

171 172 173
    uint8_t offset = 0;
    uint8_t cListEntries = 0;
    uint8_t cBytes = listAck->hdr.size;
174

175 176 177
    // parse filenames out of the buffer
    while (offset < cBytes) {
        const char * ptr = ((const char *)listAck->data) + offset;
178

179 180
        // get the length of the name
        uint8_t cBytesLeft = cBytes - offset;
Don Gagne's avatar
Don Gagne committed
181
        uint8_t nlen = static_cast<uint8_t>(strnlen(ptr, cBytesLeft));
182
        if ((*ptr == 'S' && nlen > 1) || (*ptr != 'S' && nlen < 2)) {
183 184 185 186 187 188 189 190
            _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;
        }
191

192
        // Returned names are prepended with D for directory, F for file, S for skip
193 194
        if (*ptr == 'F' || *ptr == 'D') {
            // put it in the view
195
            _emitListEntry(ptr);
196 197
        } else if (*ptr == 'S') {
            // do nothing
198 199
        } else {
            qDebug() << "unknown entry" << ptr;
200
        }
201

202 203
        // account for the name + NUL
        offset += nlen + 1;
204

205 206 207
        cListEntries++;
    }

Don Gagne's avatar
Don Gagne committed
208
    if (listAck->hdr.size == 0 || cListEntries == 0) {
209 210 211
        // Directory is empty, we're done
        Q_ASSERT(listAck->hdr.opcode == kRspAck);
        _currentOperation = kCOIdle;
Don Gagne's avatar
Don Gagne committed
212
        emit commandComplete();
213 214
    } else {
        // Possibly more entries to come, need to keep trying till we get EOF
215 216 217
        _currentOperation = kCOList;
        _listOffset += cListEntries;
        _sendListCommand();
218 219 220
    }
}

221
/// @brief Respond to the Ack associated with the create command.
222
void FileManager::_createAckResponse(Request* createAck)
223
{
Don Gagne's avatar
Don Gagne committed
224 225
    qCDebug(FileManagerLog) << "_createAckResponse";
    
226 227 228
    _currentOperation = kCOWrite;
    _activeSession = createAck->hdr.session;

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

Don Gagne's avatar
Don Gagne committed
231
    _writeOffset = 0;
232
    _writeSize = 0;
Don Gagne's avatar
Don Gagne committed
233
    
234 235 236 237
    _writeFileDatablock();
}

/// @brief Respond to the Ack associated with the write command.
238
void FileManager::_writeAckResponse(Request* writeAck)
239
{
240
    if(_writeOffset + _writeSize >= _writeFileSize){
Don Gagne's avatar
Don Gagne committed
241
        _closeUploadSession(true /* success */);
242 243
    }

244
    if (writeAck->hdr.session != _activeSession) {
Don Gagne's avatar
Don Gagne committed
245
        _closeUploadSession(false /* failure */);
246 247 248 249 250
        _emitErrorMessage(tr("Write: Incorrect session returned"));
        return;
    }

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

256
    if (writeAck->hdr.size != sizeof(uint32_t)) {
Don Gagne's avatar
Don Gagne committed
257
        _closeUploadSession(false /* failure */);
258
        _emitErrorMessage(tr("Write: Returned invalid size of write size data"));
259 260 261
        return;
    }

262

Don Gagne's avatar
Don Gagne committed
263 264
    if( writeAck->writeFileLength !=_writeSize) {
        _closeUploadSession(false /* failure */);
265
        _emitErrorMessage(tr("Write: Size returned (%1) differs from size requested (%2)").arg(writeAck->writeFileLength).arg(_writeSize));
266 267 268 269 270 271 272
        return;
    }

    _writeFileDatablock();
}

/// @brief Send next write file data block.
273
void FileManager::_writeFileDatablock(void)
274
{
Don Gagne's avatar
Don Gagne committed
275 276
    if (_writeOffset + _writeSize >= _writeFileSize){
        _closeUploadSession(true /* success */);
277
        return;
278 279
    }

280 281
    _writeOffset += _writeSize;

282 283 284 285 286
    Request request;
    request.hdr.session = _activeSession;
    request.hdr.opcode = kCmdWriteFile;
    request.hdr.offset = _writeOffset;

287
    if(_writeFileSize -_writeOffset > sizeof(request.data) )
288 289
        _writeSize = sizeof(request.data);
    else
290
        _writeSize = _writeFileSize - _writeOffset;
291 292 293

    request.hdr.size = _writeSize;

294
    memcpy(request.data, &_writeFileAccumulator.data()[_writeOffset], _writeSize);
295 296 297 298

    _sendRequest(&request);
}

299
void FileManager::receiveMessage(mavlink_message_t message)
Lorenz Meier's avatar
Lorenz Meier committed
300
{
301 302
    // 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) {
303 304
        return;
    }
305
	
306 307
    mavlink_file_transfer_protocol_t data;
    mavlink_msg_file_transfer_protocol_decode(&message, &data);
308
	
309 310
    // Make sure we are the target system
    if (data.target_system != _systemIdQGC) {
311
        qDebug() << "Received MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL with incorrect target_system:" <<  data.target_system << "expected:" << _systemIdQGC;
312 313
        return;
    }
314 315 316
    
    Request* request = (Request*)&data.payload[0];
    
317 318
    _clearAckTimeout();
    
319 320
	qCDebug(FileManagerLog) << "receiveMessage" << request->hdr.opcode;
	
321
    uint16_t incomingSeqNumber = request->hdr.seqNumber;
322 323 324 325
    
    // Make sure we have a good sequence number
    uint16_t expectedSeqNumber = _lastOutgoingSeqNumber + 1;
    if (incomingSeqNumber != expectedSeqNumber) {
Don Gagne's avatar
Don Gagne committed
326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349
        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;
        }
        
350 351 352 353 354 355
        _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;
356

357
    if (request->hdr.opcode == kRspAck) {
358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376
        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:
377 378
                _createAckResponse(request);
                break;
379 380
                
            case kCmdWriteFile:
381 382
                _writeAckResponse(request);
                break;
383 384 385 386 387 388
                
			default:
				// Ack back from operation which does not require additional work
				_currentOperation = kCOIdle;
				break;
		}
389
    } else if (request->hdr.opcode == kRspNak) {
390
        uint8_t errorCode = request->data[0];
391

392 393 394
        // 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);
        
395
        _currentOperation = kCOIdle;
396

397 398
        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
399
            emit commandComplete();
400
            return;
401 402 403
        } 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 */);
404
            return;
405
        } else if (request->hdr.req_opcode == kCmdCreateFile) {
406 407
            _emitErrorMessage(tr("Nak received creating file, error: %1").arg(errorString(request->data[0])));
            return;
408 409
        } else {
            // Generic Nak handling
410 411 412
            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
413 414 415
            } else if (request->hdr.req_opcode == kCmdWriteFile) {
                // Nak error during upload loop, upload failed
                _closeUploadSession(false /* failure */);
416 417 418
            }
            _emitErrorMessage(tr("Nak received, error: %1").arg(errorString(request->data[0])));
        }
419 420 421
    } else {
        // Note that we don't change our operation state. If something goes wrong beyond this, the operation
        // will time out.
422
        _emitErrorMessage(tr("Unknown opcode returned from server: %1").arg(request->hdr.opcode));
Lorenz Meier's avatar
Lorenz Meier committed
423 424 425
    }
}

426
void FileManager::listDirectory(const QString& dirPath)
Lorenz Meier's avatar
Lorenz Meier committed
427
{
428 429 430
    if (_currentOperation != kCOIdle) {
        _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
        return;
none's avatar
none committed
431 432
    }

433 434 435 436 437 438
    _dedicatedLink = _vehicle->priorityLink();
    if (!_dedicatedLink) {
        _emitErrorMessage(tr("Command not sent. No Vehicle links."));
        return;
    }

none's avatar
none committed
439
    // initialise the lister
440
    _listPath = dirPath;
441 442
    _listOffset = 0;
    _currentOperation = kCOList;
none's avatar
none committed
443 444

    // and send the initial request
445
    _sendListCommand();
none's avatar
none committed
446 447
}

448
void FileManager::_fillRequestWithString(Request* request, const QString& str)
449 450
{
    strncpy((char *)&request->data[0], str.toStdString().c_str(), sizeof(request->data));
Don Gagne's avatar
Don Gagne committed
451
    request->hdr.size = static_cast<uint8_t>(strnlen((const char *)&request->data[0], sizeof(request->data)));
452 453
}

454
void FileManager::_sendListCommand(void)
none's avatar
none committed
455
{
456
    Request request;
none's avatar
none committed
457

458
    request.hdr.session = 0;
459
    request.hdr.opcode = kCmdListDirectory;
460
    request.hdr.offset = _listOffset;
461
    request.hdr.size = 0;
462

463
    _fillRequestWithString(&request, _listPath);
464

465 466
    qCDebug(FileManagerLog) << "listDirectory: path:" << _listPath << "offset:" <<  _listOffset;
    
467
    _sendRequest(&request);
Lorenz Meier's avatar
Lorenz Meier committed
468 469
}

470
void FileManager::downloadPath(const QString& from, const QDir& downloadDir)
Lorenz Meier's avatar
Lorenz Meier committed
471
{
Don Gagne's avatar
Don Gagne committed
472 473 474 475
    if (_currentOperation != kCOIdle) {
        _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
        return;
    }
476 477 478 479 480 481

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

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

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

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

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

544 545 546 547 548 549
    _dedicatedLink = _vehicle->priorityLink();
    if (!_dedicatedLink) {
        _emitErrorMessage(tr("Command not sent. No Vehicle links."));
        return;
    }

550 551 552 553
    if (toPath.isEmpty()) {
        return;
    }

Don Gagne's avatar
Don Gagne committed
554
    if (!uploadFile.isReadable()){
555
        _emitErrorMessage(tr("File (%1) is not readable for upload").arg(uploadFile.path()));
Don Gagne's avatar
Don Gagne committed
556
        return;
557 558 559
    }

    QFile file(uploadFile.absoluteFilePath());
560
    if (!file.open(QIODevice::ReadOnly)) {
561 562 563 564 565
            _emitErrorMessage(tr("Unable to open local file for upload (%1)").arg(uploadFile.absoluteFilePath()));
            return;
        }

    _writeFileAccumulator = file.readAll();
566
    _writeFileSize = _writeFileAccumulator.size();
567

568 569 570
    file.close();

    if (_writeFileAccumulator.size() == 0) {
571 572 573 574 575 576 577 578 579 580
        _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;
581
    request.hdr.size = 0;
582
    _fillRequestWithString(&request, toPath + "/" + uploadFile.fileName());
583 584 585
    _sendRequest(&request);
}

586
QString FileManager::errorString(uint8_t errorCode)
none's avatar
none committed
587 588
{
    switch(errorCode) {
589 590 591 592 593 594 595 596 597 598 599 600 601 602 603
        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
604
            return QString("no sessions available");
605 606 607 608
        case kErrFailFileExists:
            return QString("File already exists on target");
        case kErrFailFileProtected:
            return QString("File is write protected");
609 610
        default:
            return QString("unknown error code");
none's avatar
none committed
611 612
    }
}
613 614 615 616 617

/// @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
618
bool FileManager::_sendOpcodeOnlyCmd(uint8_t opcode, OperationState newOpState)
619 620 621 622 623
{
    if (_currentOperation != kCOIdle) {
        // Can't have multiple commands in play at the same time
        return false;
    }
624

625 626 627 628 629
    Request request;
    request.hdr.session = 0;
    request.hdr.opcode = opcode;
    request.hdr.offset = 0;
    request.hdr.size = 0;
630

631
    _currentOperation = newOpState;
632

633
    _sendRequest(&request);
634

635
    return true;
636 637 638
}

/// @brief Starts the ack timeout timer
639
void FileManager::_setupAckTimeout(void)
640
{
641 642
	qCDebug(FileManagerLog) << "_setupAckTimeout";

643
    Q_ASSERT(!_ackTimer.isActive());
644

645
    _ackTimer.setSingleShot(true);
Don Gagne's avatar
Don Gagne committed
646
    _ackTimer.start(ackTimerTimeoutMsecs);
647 648 649
}

/// @brief Clears the ack timeout timer
650
void FileManager::_clearAckTimeout(void)
651
{
652
	qCDebug(FileManagerLog) << "_clearAckTimeout";
653 654 655 656
    _ackTimer.stop();
}

/// @brief Called when ack timeout timer fires
657
void FileManager::_ackTimeout(void)
658
{
659 660
    qCDebug(FileManagerLog) << "_ackTimeout";
    
Don Gagne's avatar
Don Gagne committed
661 662 663
    // 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.
664 665 666

    switch (_currentOperation) {
        case kCORead:
667 668
        case kCOBurst:
            _closeDownloadSession(false /* failure */);
Don Gagne's avatar
Don Gagne committed
669 670 671 672 673 674 675 676
            _emitErrorMessage(tr("Timeout waiting for ack: Download failed"));
            break;
            
        case kCOOpenRead:
        case kCOOpenBurst:
            _currentOperation = kCOIdle;
            _emitErrorMessage(tr("Timeout waiting for ack: Download failed"));
            _sendResetCommand();
677
            break;
678
            
679
        case kCOCreate:
Don Gagne's avatar
Don Gagne committed
680 681 682
            _currentOperation = kCOIdle;
            _emitErrorMessage(tr("Timeout waiting for ack: Upload failed"));
            _sendResetCommand();
683 684
            break;
            
685
        case kCOWrite:
Don Gagne's avatar
Don Gagne committed
686 687
            _closeUploadSession(false /* failure */);
            _emitErrorMessage(tr("Timeout waiting for ack: Upload failed"));
688
            break;
689
			
690 691
        default:
            _currentOperation = kCOIdle;
Don Gagne's avatar
Don Gagne committed
692
            _emitErrorMessage(QString("Timeout waiting for ack: Command failed (%1)").arg(_currentOperation));
693 694 695 696
            break;
    }
}

Don Gagne's avatar
Don Gagne committed
697
void FileManager::_sendResetCommand(void)
698 699
{
    Request request;
Don Gagne's avatar
Don Gagne committed
700
    request.hdr.opcode = kCmdResetSessions;
701
    request.hdr.size = 0;
702
    _sendRequest(&request);
703 704
}

705
void FileManager::_emitErrorMessage(const QString& msg)
706
{
707
	qCDebug(FileManagerLog) << "Error:" << msg;
Don Gagne's avatar
Don Gagne committed
708
    emit commandError(msg);
709 710
}

711
void FileManager::_emitListEntry(const QString& entry)
712
{
713
    qCDebug(FileManagerLog) << "_emitListEntry" << entry;
714
    emit listEntry(entry);
715 716
}

717
/// @brief Sends the specified Request out to the UAS.
718
void FileManager::_sendRequest(Request* request)
719
{
720

721
    mavlink_message_t message;
722

723
    _setupAckTimeout();
724 725
    
    _lastOutgoingSeqNumber++;
726

727 728
    request->hdr.seqNumber = _lastOutgoingSeqNumber;
    
Don Gagne's avatar
Don Gagne committed
729 730
    qCDebug(FileManagerLog) << "_sendRequest opcode:" << request->hdr.opcode << "seqNumber:" << request->hdr.seqNumber;
    
731
    if (_systemIdQGC == 0) {
732
        _systemIdQGC = qgcApp()->toolbox()->mavlinkProtocol()->getSystemId();
733
    }
Don Gagne's avatar
Don Gagne committed
734 735 736 737 738 739 740 741

    // 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();
    }
742
    
743 744
    mavlink_msg_file_transfer_protocol_pack_chan(_systemIdQGC,       // QGC System ID
                                                 0,                  // QGC Component ID
Don Gagne's avatar
Don Gagne committed
745
                                                 link->mavlinkChannel(),
746 747 748 749 750
                                                 &message,           // Mavlink Message to pack into
                                                 0,                  // Target network
                                                 _systemIdServer,    // Target system
                                                 0,                  // Target component
                                                 (uint8_t*)request); // Payload
751
    
Don Gagne's avatar
Don Gagne committed
752
    _vehicle->sendMessageOnLink(link, message);
Lorenz Meier's avatar
Lorenz Meier committed
753
}