QGCUASFileManager.cc 15.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 25
#include "QGCUASFileManager.h"
#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

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

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

62 63
    _readOffset = 0;                // Start reading at beginning of file
    _readFileAccumulator.clear();   // Start with an empty file
64

65 66
    Request request;
    request.hdr.session = _activeSession;
67
    request.hdr.opcode = kCmdReadFile;
68 69
    request.hdr.offset = _readOffset;
    request.hdr.size = sizeof(request.data);
70

71 72 73
    _sendRequest(&request);
}

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

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

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

95
        emit downloadFileComplete();
96
    }
97

98 99 100 101
    // Close the open session
    _sendTerminateCommand();
}

102
/// @brief Respond to the Ack associated with the Read command.
103
void QGCUASFileManager::_readAckResponse(Request* readAck)
104 105 106 107 108 109 110
{
    if (readAck->hdr.session != _activeSession) {
        _currentOperation = kCOIdle;
        _readFileAccumulator.clear();
        _emitErrorMessage(tr("Read: Incorrect session returned"));
        return;
    }
111

112 113 114 115 116 117 118 119
    if (readAck->hdr.offset != _readOffset) {
        _currentOperation = kCOIdle;
        _readFileAccumulator.clear();
        _emitErrorMessage(tr("Read: Offset returned (%1) differs from offset requested (%2)").arg(readAck->hdr.offset).arg(_readOffset));
        return;
    }

    _readFileAccumulator.append((const char*)readAck->data, readAck->hdr.size);
120
    emit downloadFileProgress(_readFileAccumulator.length());
121

122 123
    if (readAck->hdr.size == sizeof(readAck->data)) {
        // Possibly still more data to read, send next read request
124

125
        _currentOperation = kCORead;
126

127
        _readOffset += readAck->hdr.size;
128

129 130
        Request request;
        request.hdr.session = _activeSession;
131
        request.hdr.opcode = kCmdReadFile;
132
        request.hdr.offset = _readOffset;
133
        request.hdr.size = 0;
134

135 136
        _sendRequest(&request);
    } else {
137
        // We only receieved a partial buffer back. These means we are at EOF
138
        _currentOperation = kCOIdle;
139
        _closeReadSession(true /* success */);
140 141 142 143 144 145 146 147 148 149 150
    }
}

/// @brief Respond to the Ack associated with the List command.
void QGCUASFileManager::_listAckResponse(Request* listAck)
{
    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;
    }
151

152 153 154
    uint8_t offset = 0;
    uint8_t cListEntries = 0;
    uint8_t cBytes = listAck->hdr.size;
155

156 157 158
    // parse filenames out of the buffer
    while (offset < cBytes) {
        const char * ptr = ((const char *)listAck->data) + offset;
159

160 161 162 163 164 165 166 167 168 169 170 171
        // get the length of the name
        uint8_t cBytesLeft = cBytes - offset;
        size_t nlen = strnlen(ptr, cBytesLeft);
        if (nlen < 2) {
            _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;
        }
172

Don Gagne's avatar
Don Gagne committed
173
        // Returned names are prepended with D for directory, F for file, U for unknown
174 175
        if (*ptr == 'F' || *ptr == 'D') {
            // put it in the view
176 177 178
            _emitListEntry(ptr);
        } else {
            qDebug() << "unknown entry" << ptr;
179
        }
180

181 182
        // account for the name + NUL
        offset += nlen + 1;
183

184 185 186
        cListEntries++;
    }

187 188 189 190
    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
191
        emit listComplete();
192 193
    } else {
        // Possibly more entries to come, need to keep trying till we get EOF
194 195 196
        _currentOperation = kCOList;
        _listOffset += cListEntries;
        _sendListCommand();
197 198 199
    }
}

Lorenz Meier's avatar
Lorenz Meier committed
200 201
void QGCUASFileManager::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
202
    Q_UNUSED(link);
203

204 205
    // 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) {
206 207
        return;
    }
208
    
209 210 211 212 213 214
    mavlink_file_transfer_protocol_t data;
    mavlink_msg_file_transfer_protocol_decode(&message, &data);
    
    // Make sure we are the target system
    if (data.target_system != _systemIdQGC) {
        qDebug() << "Received MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL with possibly incorrect system id" << _systemIdQGC;
215 216
        return;
    }
217 218 219
    
    Request* request = (Request*)&data.payload[0];
    
220 221
    _clearAckTimeout();
    
222
    uint16_t incomingSeqNumber = request->hdr.seqNumber;
223 224 225 226 227 228 229 230 231 232 233
    
    // 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;
234

235
    if (request->hdr.opcode == kRspAck) {
236

237 238 239 240 241
        switch (_currentOperation) {
            case kCOIdle:
                // we should not be seeing anything here.. shut the other guy up
                _sendCmdReset();
                break;
242

243 244 245 246
            case kCOAck:
                // We are expecting an ack back
                _currentOperation = kCOIdle;
                break;
247

248
            case kCOList:
249
                _listAckResponse(request);
250
                break;
251

252
            case kCOOpen:
253
                _openAckResponse(request);
254
                break;
255

256
            case kCORead:
257
                _readAckResponse(request);
258 259
                break;

260
            default:
Don Gagne's avatar
Don Gagne committed
261
                _emitErrorMessage(tr("Ack received in unexpected state"));
262 263 264
                break;
        }
    } else if (request->hdr.opcode == kRspNak) {
265
        Q_ASSERT(request->hdr.size == 1); // Should only have one byte of error code
266

267 268
        OperationState previousOperation = _currentOperation;
        uint8_t errorCode = request->data[0];
269

270
        _currentOperation = kCOIdle;
271

272 273
        if (previousOperation == kCOList && errorCode == kErrEOF) {
            // This is not an error, just the end of the read loop
Don Gagne's avatar
Don Gagne committed
274
            emit listComplete();
275 276 277 278 279 280 281 282 283 284 285 286 287
            return;
        } else if (previousOperation == kCORead && errorCode == kErrEOF) {
            // This is not an error, just the end of the read loop
            _closeReadSession(true /* success */);
            return;
        } else {
            // Generic Nak handling
            if (previousOperation == kCORead) {
                // Nak error during read loop, download failed
                _closeReadSession(false /* failure */);
            }
            _emitErrorMessage(tr("Nak received, error: %1").arg(errorString(request->data[0])));
        }
288 289 290
    } else {
        // Note that we don't change our operation state. If something goes wrong beyond this, the operation
        // will time out.
291
        _emitErrorMessage(tr("Unknown opcode returned from server: %1").arg(request->hdr.opcode));
Lorenz Meier's avatar
Lorenz Meier committed
292 293 294
    }
}

295
void QGCUASFileManager::listDirectory(const QString& dirPath)
Lorenz Meier's avatar
Lorenz Meier committed
296
{
297 298 299
    if (_currentOperation != kCOIdle) {
        _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
        return;
none's avatar
none committed
300 301 302
    }

    // initialise the lister
303
    _listPath = dirPath;
304 305
    _listOffset = 0;
    _currentOperation = kCOList;
none's avatar
none committed
306 307

    // and send the initial request
308
    _sendListCommand();
none's avatar
none committed
309 310
}

311 312 313 314 315 316
void QGCUASFileManager::_fillRequestWithString(Request* request, const QString& str)
{
    strncpy((char *)&request->data[0], str.toStdString().c_str(), sizeof(request->data));
    request->hdr.size = strnlen((const char *)&request->data[0], sizeof(request->data));
}

317
void QGCUASFileManager::_sendListCommand(void)
none's avatar
none committed
318
{
319
    Request request;
none's avatar
none committed
320

321
    request.hdr.session = 0;
322
    request.hdr.opcode = kCmdListDirectory;
323
    request.hdr.offset = _listOffset;
324
    request.hdr.size = 0;
325

326
    _fillRequestWithString(&request, _listPath);
327

328
    _sendRequest(&request);
Lorenz Meier's avatar
Lorenz Meier committed
329 330
}

331 332 333 334
/// @brief Downloads the specified file.
///     @param from File to download from UAS, fully qualified path
///     @param downloadDir Local directory to download file to
void QGCUASFileManager::downloadPath(const QString& from, const QDir& downloadDir)
Lorenz Meier's avatar
Lorenz Meier committed
335
{
336 337 338
    if (from.isEmpty()) {
        return;
    }
339

340
    _readFileDownloadDir.setPath(downloadDir.absolutePath());
341

342 343 344 345 346 347 348 349 350 351
    // 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);
352

353
    _currentOperation = kCOOpen;
Lorenz Meier's avatar
Lorenz Meier committed
354

355 356
    Request request;
    request.hdr.session = 0;
357
    request.hdr.opcode = kCmdOpenFile;
358
    request.hdr.offset = 0;
359
    request.hdr.size = 0;
360 361
    _fillRequestWithString(&request, from);
    _sendRequest(&request);
362
}
none's avatar
none committed
363 364 365 366

QString QGCUASFileManager::errorString(uint8_t errorCode)
{
    switch(errorCode) {
367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384
        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");
        default:
            return QString("unknown error code");
none's avatar
none committed
385 386
    }
}
387 388 389 390 391 392 393 394 395 396 397

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

399 400 401 402 403
    Request request;
    request.hdr.session = 0;
    request.hdr.opcode = opcode;
    request.hdr.offset = 0;
    request.hdr.size = 0;
404

405
    _currentOperation = newOpState;
406

407
    _sendRequest(&request);
408

409
    return true;
410 411 412 413 414 415
}

/// @brief Starts the ack timeout timer
void QGCUASFileManager::_setupAckTimeout(void)
{
    Q_ASSERT(!_ackTimer.isActive());
416

417
    _ackTimer.setSingleShot(true);
Don Gagne's avatar
Don Gagne committed
418
    _ackTimer.start(ackTimerTimeoutMsecs);
419 420 421 422 423 424 425 426 427 428 429
}

/// @brief Clears the ack timeout timer
void QGCUASFileManager::_clearAckTimeout(void)
{
    _ackTimer.stop();
}

/// @brief Called when ack timeout timer fires
void QGCUASFileManager::_ackTimeout(void)
{
Don Gagne's avatar
Don Gagne committed
430 431 432
    // 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.
433 434 435 436

    switch (_currentOperation) {
        case kCORead:
            _currentOperation = kCOAck;
Don Gagne's avatar
Don Gagne committed
437
            _emitErrorMessage(tr("Timeout waiting for ack: Sending Terminate command"));
438 439 440 441
            _sendTerminateCommand();
            break;
        default:
            _currentOperation = kCOIdle;
Don Gagne's avatar
Don Gagne committed
442
            _emitErrorMessage(tr("Timeout waiting for ack"));
443 444 445 446 447 448 449 450
            break;
    }
}

void QGCUASFileManager::_sendTerminateCommand(void)
{
    Request request;
    request.hdr.session = _activeSession;
451
    request.hdr.opcode = kCmdTerminateSession;
452
    request.hdr.size = 0;
453
    _sendRequest(&request);
454 455 456 457
}

void QGCUASFileManager::_emitErrorMessage(const QString& msg)
{
458
    qDebug() << "QGCUASFileManager: Error" << msg;
459 460 461
    emit errorMessage(msg);
}

462
void QGCUASFileManager::_emitListEntry(const QString& entry)
463
{
464 465
    qDebug() << "QGCUASFileManager: list entry" << entry;
    emit listEntry(entry);
466 467
}

468 469 470 471
/// @brief Sends the specified Request out to the UAS.
void QGCUASFileManager::_sendRequest(Request* request)
{
    mavlink_message_t message;
472

473
    _setupAckTimeout();
474 475
    
    _lastOutgoingSeqNumber++;
476

477
    request->hdr.seqNumber = _lastOutgoingSeqNumber;
Vladimir Ermakov's avatar
Vladimir Ermakov committed
478 479 480
    request->hdr.reserved[0] = 0;
    request->hdr.reserved[1] = 0;
    request->hdr.reserved[2] = 0;
481 482 483 484 485 486 487 488 489 490 491 492 493 494
    
    if (_systemIdQGC == 0) {
        _systemIdQGC = MainWindow::instance()->getMAVLink()->getSystemId();
    }
    
    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
    
495
    _mav->sendMessage(message);
Lorenz Meier's avatar
Lorenz Meier committed
496
}