FileManager.cc 22.3 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"
Lorenz Meier's avatar
Lorenz Meier committed
28 29 30

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

33
QGC_LOGGING_CATEGORY(FileManagerLog, "FileManagerLog")
34

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

51
/// @brief Respond to the Ack associated with the Open command with the next Read command.
52
void FileManager::_openAckResponse(Request* openAck)
53
{
54 55
	Q_ASSERT(_currentOperation == kCOOpenRead || _currentOperation == kCOOpenStream);
	_currentOperation = _currentOperation == kCOOpenRead ? kCORead : kCOBurst;
56
    _activeSession = openAck->hdr.session;
57 58 59
    
    // File length comes back in data
    Q_ASSERT(openAck->hdr.size == sizeof(uint32_t));
60 61 62
    emit downloadFileLength(openAck->openFileLength);
    
    // Start the sequence of read commands
63

64
    _downloadOffset = 0;                // Start reading at beginning of file
65
    _readFileAccumulator.clear();   // Start with an empty file
66

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

74 75 76
    _sendRequest(&request);
}

77 78
/// @brief Closes out a read session by writing the file and doing cleanup.
///     @param success true: successful download completion, false: error during download
79
void FileManager::_closeDownloadSession(bool success)
80 81 82
{
    if (success) {
        QString downloadFilePath = _readFileDownloadDir.absoluteFilePath(_readFileDownloadFilename);
83

84 85 86 87 88
        QFile file(downloadFilePath);
        if (!file.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
            _emitErrorMessage(tr("Unable to open local file for writing (%1)").arg(downloadFilePath));
            return;
        }
89

90 91 92 93 94 95 96
        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();
97

98
        emit downloadFileComplete();
99
    }
100

101 102 103 104
    // Close the open session
    _sendTerminateCommand();
}

105 106 107
/// 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)
108 109 110 111
{
    if (readAck->hdr.session != _activeSession) {
        _currentOperation = kCOIdle;
        _readFileAccumulator.clear();
112
        _emitErrorMessage(tr("Download: Incorrect session returned"));
113 114
        return;
    }
115

116
    if (readAck->hdr.offset != _downloadOffset) {
117 118
        _currentOperation = kCOIdle;
        _readFileAccumulator.clear();
119
        _emitErrorMessage(tr("Download: Offset returned (%1) differs from offset requested/expected (%2)").arg(readAck->hdr.offset).arg(_downloadOffset));
120 121
        return;
    }
122 123
    
    qCDebug(FileManagerLog) << QString("_downloadAckResponse: offset(%1) size(%2) burstComplete(%3)").arg(readAck->hdr.offset).arg(readAck->hdr.size).arg(readAck->hdr.burstComplete);
124

125
	_downloadOffset += readAck->hdr.size;
126
    _readFileAccumulator.append((const char*)readAck->data, readAck->hdr.size);
127
    emit downloadFileProgress(_readFileAccumulator.length());
128

129
    if (readAck->hdr.size == sizeof(readAck->data)) {
130 131 132 133 134 135 136 137 138 139 140 141 142 143 144
		if (readFile || readAck->hdr.burstComplete) {
			// Possibly still more data to read, send next read request

			Request request;
			request.hdr.session = _activeSession;
            request.hdr.opcode = readFile ? kCmdReadFile : kCmdBurstReadFile;
			request.hdr.offset = _downloadOffset;
			request.hdr.size = 0;

			_sendRequest(&request);
		} else {
			// Streaming, so next ack should come automatically
			_setupAckTimeout();
		}
    } else if (readFile) {
145
        // We only receieved a partial buffer back. These means we are at EOF
146
        _currentOperation = kCOIdle;
147
        _closeDownloadSession(true /* success */);
148 149 150 151
    }
}

/// @brief Respond to the Ack associated with the List command.
152
void FileManager::_listAckResponse(Request* listAck)
153 154 155 156 157 158
{
    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;
    }
159

160 161 162
    uint8_t offset = 0;
    uint8_t cListEntries = 0;
    uint8_t cBytes = listAck->hdr.size;
163

164 165 166
    // parse filenames out of the buffer
    while (offset < cBytes) {
        const char * ptr = ((const char *)listAck->data) + offset;
167

168 169
        // get the length of the name
        uint8_t cBytesLeft = cBytes - offset;
Don Gagne's avatar
Don Gagne committed
170
        uint8_t nlen = static_cast<uint8_t>(strnlen(ptr, cBytesLeft));
171
        if ((*ptr == 'S' && nlen > 1) || (*ptr != 'S' && nlen < 2)) {
172 173 174 175 176 177 178 179
            _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;
        }
180

181
        // Returned names are prepended with D for directory, F for file, S for skip
182 183
        if (*ptr == 'F' || *ptr == 'D') {
            // put it in the view
184
            _emitListEntry(ptr);
185 186
        } else if (*ptr == 'S') {
            // do nothing
187 188
        } else {
            qDebug() << "unknown entry" << ptr;
189
        }
190

191 192
        // account for the name + NUL
        offset += nlen + 1;
193

194 195 196
        cListEntries++;
    }

197 198 199 200
    if (listAck->hdr.size == 0) {
        // Directory is empty, we're done
        Q_ASSERT(listAck->hdr.opcode == kRspAck);
        _currentOperation = kCOIdle;
Don Gagne's avatar
Don Gagne committed
201
        emit listComplete();
202 203
    } else {
        // Possibly more entries to come, need to keep trying till we get EOF
204 205 206
        _currentOperation = kCOList;
        _listOffset += cListEntries;
        _sendListCommand();
207 208 209
    }
}

210
/// @brief Respond to the Ack associated with the create command.
211
void FileManager::_createAckResponse(Request* createAck)
212 213 214 215 216 217 218 219 220 221 222 223 224
{
    _currentOperation = kCOWrite;
    _activeSession = createAck->hdr.session;

    // Start the sequence of read commands

    _writeOffset = 0;                // Start writing at beginning of file
    _writeSize = 0;

    _writeFileDatablock();
}

/// @brief Respond to the Ack associated with the write command.
225
void FileManager::_writeAckResponse(Request* writeAck)
226
{
227 228 229 230 231 232 233
    if(_writeOffset + _writeSize >= _writeFileSize){
        _writeFileAccumulator.clear();
        _writeFileSize = 0;
        _currentOperation = kCOIdle;
        emit uploadFileComplete();
    }

234 235 236 237 238 239 240 241 242 243 244 245 246 247
    if (writeAck->hdr.session != _activeSession) {
        _currentOperation = kCOIdle;
        _writeFileAccumulator.clear();
        _emitErrorMessage(tr("Write: Incorrect session returned"));
        return;
    }

    if (writeAck->hdr.offset != _writeOffset) {
        _currentOperation = kCOIdle;
        _writeFileAccumulator.clear();
        _emitErrorMessage(tr("Write: Offset returned (%1) differs from offset requested (%2)").arg(writeAck->hdr.offset).arg(_writeOffset));
        return;
    }

248
    if (writeAck->hdr.size != sizeof(uint32_t)) {
249 250
        _currentOperation = kCOIdle;
        _writeFileAccumulator.clear();
251
        _emitErrorMessage(tr("Write: Returned invalid size of write size data"));
252 253 254
        return;
    }

255

256
    if( writeAck->writeFileLength !=_writeSize){
257 258
        _currentOperation = kCOIdle;
        _writeFileAccumulator.clear();
259
        _emitErrorMessage(tr("Write: Size returned (%1) differs from size requested (%2)").arg(writeAck->writeFileLength).arg(_writeSize));
260 261 262 263 264 265 266
        return;
    }

    _writeFileDatablock();
}

/// @brief Send next write file data block.
267
void FileManager::_writeFileDatablock(void)
268 269 270 271 272 273
{
    /// @brief Maximum data size in RequestHeader::data
//	static const uint8_t	kMaxDataLength = MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(RequestHeader);
//    static const uint8_t	kMaxDataLength = Request.data;

    if(_writeOffset + _writeSize >= _writeFileSize){
274 275
        _sendTerminateCommand();
        return;
276 277
    }

278 279
    _writeOffset += _writeSize;

280 281 282 283 284
    Request request;
    request.hdr.session = _activeSession;
    request.hdr.opcode = kCmdWriteFile;
    request.hdr.offset = _writeOffset;

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

    request.hdr.size = _writeSize;

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

    _sendRequest(&request);
}

297
void FileManager::receiveMessage(LinkInterface* link, mavlink_message_t message)
Lorenz Meier's avatar
Lorenz Meier committed
298
{
299
    Q_UNUSED(link);
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 326 327 328 329 330 331 332
    
    // Make sure we have a good sequence number
    uint16_t expectedSeqNumber = _lastOutgoingSeqNumber + 1;
    if (incomingSeqNumber != expectedSeqNumber) {
        _currentOperation = kCOIdle;
        _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;
333

334
    if (request->hdr.opcode == kRspAck) {
335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353
        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:
354 355
                _createAckResponse(request);
                break;
356 357
                
            case kCmdWriteFile:
358 359
                _writeAckResponse(request);
                break;
360 361 362 363 364 365
                
			default:
				// Ack back from operation which does not require additional work
				_currentOperation = kCOIdle;
				break;
		}
366
    } else if (request->hdr.opcode == kRspNak) {
367
        uint8_t errorCode = request->data[0];
368

369 370 371
        // 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);
        
372
        _currentOperation = kCOIdle;
373

374 375
        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
376
            emit listComplete();
377
            return;
378 379 380
        } 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 */);
381
            return;
382 383 384 385 386
        } else if (previousOperation == kCOCreate) {
            // End a failed create file operation
            _sendTerminateCommand();
            _emitErrorMessage(tr("Nak received creating file, error: %1").arg(errorString(request->data[0])));
            return;
387 388
        } else {
            // Generic Nak handling
389 390 391
            if (request->hdr.req_opcode == kCmdReadFile || request->hdr.req_opcode == kCmdBurstReadFile) {
                // Nak error during download loop, download failed
                _closeDownloadSession(false /* failure */);
392 393 394
            }
            _emitErrorMessage(tr("Nak received, error: %1").arg(errorString(request->data[0])));
        }
395 396 397
    } else {
        // Note that we don't change our operation state. If something goes wrong beyond this, the operation
        // will time out.
398
        _emitErrorMessage(tr("Unknown opcode returned from server: %1").arg(request->hdr.opcode));
Lorenz Meier's avatar
Lorenz Meier committed
399 400 401
    }
}

402
void FileManager::listDirectory(const QString& dirPath)
Lorenz Meier's avatar
Lorenz Meier committed
403
{
404 405 406
    if (_currentOperation != kCOIdle) {
        _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
        return;
none's avatar
none committed
407 408 409
    }

    // initialise the lister
410
    _listPath = dirPath;
411 412
    _listOffset = 0;
    _currentOperation = kCOList;
none's avatar
none committed
413 414

    // and send the initial request
415
    _sendListCommand();
none's avatar
none committed
416 417
}

418
void FileManager::_fillRequestWithString(Request* request, const QString& str)
419 420
{
    strncpy((char *)&request->data[0], str.toStdString().c_str(), sizeof(request->data));
Don Gagne's avatar
Don Gagne committed
421
    request->hdr.size = static_cast<uint8_t>(strnlen((const char *)&request->data[0], sizeof(request->data)));
422 423
}

424
void FileManager::_sendListCommand(void)
none's avatar
none committed
425
{
426
    Request request;
none's avatar
none committed
427

428
    request.hdr.session = 0;
429
    request.hdr.opcode = kCmdListDirectory;
430
    request.hdr.offset = _listOffset;
431
    request.hdr.size = 0;
432

433
    _fillRequestWithString(&request, _listPath);
434

435 436
    qCDebug(FileManagerLog) << "listDirectory: path:" << _listPath << "offset:" <<  _listOffset;
    
437
    _sendRequest(&request);
Lorenz Meier's avatar
Lorenz Meier committed
438 439
}

440
void FileManager::downloadPath(const QString& from, const QDir& downloadDir)
Lorenz Meier's avatar
Lorenz Meier committed
441
{
442 443 444
	qCDebug(FileManagerLog) << "downloadPath from:" << from << "to:" << downloadDir;
	_downloadWorker(from, downloadDir, true /* read file */);
}
445

446 447 448 449 450
void FileManager::streamPath(const QString& from, const QDir& downloadDir)
{
	qCDebug(FileManagerLog) << "streamPath from:" << from << "to:" << downloadDir;
	_downloadWorker(from, downloadDir, false /* stream file */);
}
Lorenz Meier's avatar
Lorenz Meier committed
451

452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479
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);
	
	_currentOperation = readFile ? kCOOpenRead : kCOOpenStream;
	
	Request request;
	request.hdr.session = 0;
	request.hdr.opcode = kCmdOpenFileRO;
	request.hdr.offset = 0;
	request.hdr.size = 0;
	_fillRequestWithString(&request, from);
	_sendRequest(&request);
480
}
none's avatar
none committed
481

482 483 484
/// @brief Uploads the specified file.
///     @param toPath File in UAS to upload to, fully qualified path
///     @param uploadFile Local file to upload from
485
void FileManager::uploadPath(const QString& toPath, const QFileInfo& uploadFile)
486
{
487 488 489 490 491
    if(_currentOperation != kCOIdle){
        _emitErrorMessage(tr("UAS File manager busy.  Try again later"));
        return;
    }

492 493 494 495
    if (toPath.isEmpty()) {
        return;
    }

496
    if(!uploadFile.isReadable()){
497 498 499 500
        _emitErrorMessage(tr("File (%1) is not readable for upload").arg(uploadFile.path()));
    }

    QFile file(uploadFile.absoluteFilePath());
501
    if (!file.open(QIODevice::ReadOnly)) {
502 503 504 505 506
            _emitErrorMessage(tr("Unable to open local file for upload (%1)").arg(uploadFile.absoluteFilePath()));
            return;
        }

    _writeFileAccumulator = file.readAll();
507
    _writeFileSize = _writeFileAccumulator.size();
508

509 510 511
    file.close();

    if (_writeFileAccumulator.size() == 0) {
512 513 514 515 516 517 518 519 520 521
        _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;
522
    request.hdr.size = 0;
523
    _fillRequestWithString(&request, toPath + "/" + uploadFile.fileName());
524 525 526
    _sendRequest(&request);
}

527
QString FileManager::errorString(uint8_t errorCode)
none's avatar
none committed
528 529
{
    switch(errorCode) {
530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545
        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");
546 547 548 549
        case kErrFailFileExists:
            return QString("File already exists on target");
        case kErrFailFileProtected:
            return QString("File is write protected");
550 551
        default:
            return QString("unknown error code");
none's avatar
none committed
552 553
    }
}
554 555 556 557 558

/// @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
559
bool FileManager::_sendOpcodeOnlyCmd(uint8_t opcode, OperationState newOpState)
560 561 562 563 564
{
    if (_currentOperation != kCOIdle) {
        // Can't have multiple commands in play at the same time
        return false;
    }
565

566 567 568 569 570
    Request request;
    request.hdr.session = 0;
    request.hdr.opcode = opcode;
    request.hdr.offset = 0;
    request.hdr.size = 0;
571

572
    _currentOperation = newOpState;
573

574
    _sendRequest(&request);
575

576
    return true;
577 578 579
}

/// @brief Starts the ack timeout timer
580
void FileManager::_setupAckTimeout(void)
581
{
582 583
	qCDebug(FileManagerLog) << "_setupAckTimeout";

584
    Q_ASSERT(!_ackTimer.isActive());
585

586
    _ackTimer.setSingleShot(true);
Don Gagne's avatar
Don Gagne committed
587
    _ackTimer.start(ackTimerTimeoutMsecs);
588 589 590
}

/// @brief Clears the ack timeout timer
591
void FileManager::_clearAckTimeout(void)
592
{
593
	qCDebug(FileManagerLog) << "_clearAckTimeout";
594 595 596 597
    _ackTimer.stop();
}

/// @brief Called when ack timeout timer fires
598
void FileManager::_ackTimeout(void)
599
{
600 601
    qCDebug(FileManagerLog) << "_ackTimeout";
    
Don Gagne's avatar
Don Gagne committed
602 603 604
    // 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.
605 606 607

    switch (_currentOperation) {
        case kCORead:
608 609
        case kCOBurst:
            _closeDownloadSession(false /* failure */);
610
            _currentOperation = kCOAck;
Don Gagne's avatar
Don Gagne committed
611
            _emitErrorMessage(tr("Timeout waiting for ack: Sending Terminate command"));
612
            break;
613
            
614
        case kCOCreate:
615 616 617 618
            _currentOperation = kCOAck;
            _writeFileAccumulator.clear();
            _emitErrorMessage(tr("Timeout waiting for ack: Sending Create command"));
            _sendTerminateCommand();
619 620
            break;
            
621 622
        case kCOWrite:
            _currentOperation = kCOAck;
623 624
            _writeFileAccumulator.clear();
            _emitErrorMessage(tr("Timeout waiting for ack: Sending Write command"));
625 626
            _sendTerminateCommand();
            break;
627
			
628 629
        default:
            _currentOperation = kCOIdle;
630
            _emitErrorMessage(QString("Timeout waiting for ack: operation (%1)").arg(_currentOperation));
631 632 633 634
            break;
    }
}

635
void FileManager::_sendTerminateCommand(void)
636 637 638
{
    Request request;
    request.hdr.session = _activeSession;
639
    request.hdr.opcode = kCmdTerminateSession;
640
    request.hdr.size = 0;
641
    _sendRequest(&request);
642 643
}

644
void FileManager::_emitErrorMessage(const QString& msg)
645
{
646
	qCDebug(FileManagerLog) << "Error:" << msg;
647 648 649
    emit errorMessage(msg);
}

650
void FileManager::_emitListEntry(const QString& entry)
651
{
652
    qCDebug(FileManagerLog) << "_emitListEntry" << entry;
653
    emit listEntry(entry);
654 655
}

656
/// @brief Sends the specified Request out to the UAS.
657
void FileManager::_sendRequest(Request* request)
658
{
659 660
	qCDebug(FileManagerLog) << "_sendRequest opcode:" << request->hdr.opcode;

661
    mavlink_message_t message;
662

663
    _setupAckTimeout();
664 665
    
    _lastOutgoingSeqNumber++;
666

667 668 669
    request->hdr.seqNumber = _lastOutgoingSeqNumber;
    
    if (_systemIdQGC == 0) {
670
        _systemIdQGC = MAVLinkProtocol::instance()->getSystemId();
671 672 673 674 675 676 677 678 679 680 681
    }
    
    Q_ASSERT(_mav);
    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
    
682
    _mav->sendMessage(message);
Lorenz Meier's avatar
Lorenz Meier committed
683
}