LogDownloadController.cc 25.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.
 *
 ****************************************************************************/
dogmaphobic's avatar
dogmaphobic committed
9 10 11 12 13


#include "LogDownloadController.h"
#include "MultiVehicleManager.h"
#include "QGCMAVLink.h"
14
#if !defined(__mobile__)
15
#include "QGCQFileDialog.h"
16 17
#include "MainWindow.h"
#endif
dogmaphobic's avatar
dogmaphobic committed
18 19 20
#include "UAS.h"
#include "QGCApplication.h"
#include "QGCToolbox.h"
21
#include "QGCMapEngine.h"
22
#include "ParameterManager.h"
dogmaphobic's avatar
dogmaphobic committed
23
#include "Vehicle.h"
24
#include "SettingsManager.h"
dogmaphobic's avatar
dogmaphobic committed
25

dogmaphobic's avatar
dogmaphobic committed
26
#include <QDebug>
dogmaphobic's avatar
dogmaphobic committed
27 28
#include <QSettings>
#include <QUrl>
Don Gagne's avatar
Don Gagne committed
29 30
#include <QBitArray>
#include <QtCore/qmath.h>
dogmaphobic's avatar
dogmaphobic committed
31 32

#define kTimeOutMilliseconds 500
33
#define kGUIRateMilliseconds 17
dogmaphobic's avatar
dogmaphobic committed
34
#define kTableBins           512
35
#define kChunkSize           (kTableBins * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN)
dogmaphobic's avatar
dogmaphobic committed
36 37 38

QGC_LOGGING_CATEGORY(LogDownloadLog, "LogDownloadLog")

39 40 41 42 43 44 45 46 47 48
//-----------------------------------------------------------------------------
struct LogDownloadData {
    LogDownloadData(QGCLogEntry* entry);
    QBitArray     chunk_table;
    uint32_t      current_chunk;
    QFile         file;
    QString       filename;
    uint          ID;
    QGCLogEntry*  entry;
    uint          written;
49 50
    size_t        rate_bytes;
    qreal         rate_avg;
51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78
    QElapsedTimer elapsed;

    void advanceChunk()
    {
           current_chunk++;
           chunk_table = QBitArray(chunkBins(), false);
    }

    // The number of MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN bins in the current chunk
    uint32_t chunkBins() const
    {
        return qMin(qCeil((entry->size() - current_chunk*kChunkSize)/static_cast<qreal>(MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN)),
                    kTableBins);
    }

    // The number of kChunkSize chunks in the file
    uint32_t numChunks() const
    {
        return qCeil(entry->size() / static_cast<qreal>(kChunkSize));
    }

    // True if all bins in the chunk have been set to val
    bool chunkEquals(const bool val) const
    {
        return chunk_table == QBitArray(chunk_table.size(), val);
    }

};
79

dogmaphobic's avatar
dogmaphobic committed
80 81 82 83 84
//----------------------------------------------------------------------------------------
LogDownloadData::LogDownloadData(QGCLogEntry* entry_)
    : ID(entry_->id())
    , entry(entry_)
    , written(0)
85 86
    , rate_bytes(0)
    , rate_avg(0)
dogmaphobic's avatar
dogmaphobic committed
87 88 89 90 91
{

}

//----------------------------------------------------------------------------------------
92
QGCLogEntry::QGCLogEntry(uint logId, const QDateTime& dateTime, uint logSize, bool received)
dogmaphobic's avatar
dogmaphobic committed
93 94 95 96 97 98
    : _logID(logId)
    , _logSize(logSize)
    , _logTimeUTC(dateTime)
    , _received(received)
    , _selected(false)
{
Gus Grubba's avatar
Gus Grubba committed
99
    _status = tr("Pending");
dogmaphobic's avatar
dogmaphobic committed
100 101
}

102 103 104 105
//----------------------------------------------------------------------------------------
QString
QGCLogEntry::sizeStr() const
{
106
    return QGCMapEngine::bigSizeToString(_logSize);
107 108
}

dogmaphobic's avatar
dogmaphobic committed
109
//----------------------------------------------------------------------------------------
110 111
LogDownloadController::LogDownloadController(void)
    : _uas(NULL)
dogmaphobic's avatar
dogmaphobic committed
112 113 114 115 116
    , _downloadData(NULL)
    , _vehicle(NULL)
    , _requestingLogEntries(false)
    , _downloadingLogs(false)
    , _retries(0)
dogmaphobic's avatar
dogmaphobic committed
117
    , _apmOneBased(0)
dogmaphobic's avatar
dogmaphobic committed
118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139
{
    MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager();
    connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &LogDownloadController::_setActiveVehicle);
    connect(&_timer, &QTimer::timeout, this, &LogDownloadController::_processDownload);
    _setActiveVehicle(manager->activeVehicle());
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::_processDownload()
{
    if(_requestingLogEntries) {
        _findMissingEntries();
    } else if(_downloadingLogs) {
        _findMissingData();
    }
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::_setActiveVehicle(Vehicle* vehicle)
{
140
    if(_uas) {
dogmaphobic's avatar
dogmaphobic committed
141 142 143 144 145
        _logEntriesModel.clear();
        disconnect(_uas, &UASInterface::logEntry, this, &LogDownloadController::_logEntry);
        disconnect(_uas, &UASInterface::logData,  this, &LogDownloadController::_logData);
        _uas = NULL;
    }
146 147 148 149 150 151
    _vehicle = vehicle;
    if(_vehicle) {
        _uas = vehicle->uas();
        connect(_uas, &UASInterface::logEntry, this, &LogDownloadController::_logEntry);
        connect(_uas, &UASInterface::logData,  this, &LogDownloadController::_logData);
    }
dogmaphobic's avatar
dogmaphobic committed
152 153 154 155 156 157 158 159 160 161 162
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::_logEntry(UASInterface* uas, uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t /*last_log_num*/)
{
    //-- Do we care?
    if(!_uas || uas != _uas || !_requestingLogEntries) {
        return;
    }
    //-- If this is the first, pre-fill it
163
    if(!_logEntriesModel.count() && num_logs > 0) {
dogmaphobic's avatar
dogmaphobic committed
164 165 166 167 168
        //-- Is this APM? They send a first entry with bogus ID and only the
        //   count is valid. From now on, all entries are 1-based.
        if(_vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
            _apmOneBased = 1;
        }
dogmaphobic's avatar
dogmaphobic committed
169 170 171 172 173 174
        for(int i = 0; i < num_logs; i++) {
            QGCLogEntry *entry = new QGCLogEntry(i);
            _logEntriesModel.append(entry);
        }
    }
    //-- Update this log record
175
    if(num_logs > 0) {
dogmaphobic's avatar
dogmaphobic committed
176
        //-- Skip if empty (APM first packet)
177
        if(size || _vehicle->firmwareType() != MAV_AUTOPILOT_ARDUPILOTMEGA) {
dogmaphobic's avatar
dogmaphobic committed
178 179 180 181 182 183
            id -= _apmOneBased;
            if(id < _logEntriesModel.count()) {
                QGCLogEntry* entry = _logEntriesModel[id];
                entry->setSize(size);
                entry->setTime(QDateTime::fromTime_t(time_utc));
                entry->setReceived(true);
Gus Grubba's avatar
Gus Grubba committed
184
                entry->setStatus(QString(tr("Available")));
dogmaphobic's avatar
dogmaphobic committed
185 186 187
            } else {
                qWarning() << "Received log entry for out-of-bound index:" << id;
            }
188
        }
dogmaphobic's avatar
dogmaphobic committed
189
    } else {
190 191
        //-- No logs to list
        _receivedAllEntries();
dogmaphobic's avatar
dogmaphobic committed
192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222
    }
    //-- Reset retry count
    _retries = 0;
    //-- Do we have it all?
    if(_entriesComplete()) {
        _receivedAllEntries();
    } else {
        //-- Reset timer
        _timer.start(kTimeOutMilliseconds);
    }
}

//----------------------------------------------------------------------------------------
bool
LogDownloadController::_entriesComplete()
{
    //-- Iterate entries and look for a gap
    int num_logs = _logEntriesModel.count();
    for(int i = 0; i < num_logs; i++) {
        QGCLogEntry* entry = _logEntriesModel[i];
        if(entry) {
            if(!entry->received()) {
               return false;
            }
        }
    }
    return true;
}

//----------------------------------------------------------------------------------------
void
dogmaphobic's avatar
dogmaphobic committed
223
LogDownloadController::_resetSelection(bool canceled)
dogmaphobic's avatar
dogmaphobic committed
224 225 226 227 228
{
    int num_logs = _logEntriesModel.count();
    for(int i = 0; i < num_logs; i++) {
        QGCLogEntry* entry = _logEntriesModel[i];
        if(entry) {
dogmaphobic's avatar
dogmaphobic committed
229 230
            if(entry->selected()) {
                if(canceled) {
Gus Grubba's avatar
Gus Grubba committed
231
                    entry->setStatus(QString(tr("Canceled")));
dogmaphobic's avatar
dogmaphobic committed
232 233 234
                }
                entry->setSelected(false);
            }
dogmaphobic's avatar
dogmaphobic committed
235 236 237 238 239 240 241 242 243 244
        }
    }
    emit selectionChanged();
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::_receivedAllEntries()
{
    _timer.stop();
dogmaphobic's avatar
dogmaphobic committed
245
    _setListing(false);
dogmaphobic's avatar
dogmaphobic committed
246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::_findMissingEntries()
{
    int start = -1;
    int end   = -1;
    int num_logs = _logEntriesModel.count();
    //-- Iterate entries and look for a gap
    for(int i = 0; i < num_logs; i++) {
        QGCLogEntry* entry = _logEntriesModel[i];
        if(entry) {
            if(!entry->received()) {
                if(start < 0)
                    start = i;
                else
                    end = i;
            } else {
                if(start >= 0) {
                    break;
                }
            }
        }
    }
    //-- Is there something missing?
    if(start >= 0) {
        //-- Have we tried too many times?
        if(_retries++ > 2) {
            for(int i = 0; i < num_logs; i++) {
                QGCLogEntry* entry = _logEntriesModel[i];
                if(entry && !entry->received()) {
Gus Grubba's avatar
Gus Grubba committed
278
                    entry->setStatus(QString(tr("Error")));
dogmaphobic's avatar
dogmaphobic committed
279 280 281 282 283 284 285 286 287 288 289
                }
            }
            //-- Give up
            _receivedAllEntries();
            qWarning() << "Too many errors retreiving log list. Giving up.";
            return;
        }
        //-- Is it a sequence or just one entry?
        if(end < 0) {
            end = start;
        }
dogmaphobic's avatar
dogmaphobic committed
290 291 292
        //-- APM "Fix"
        start += _apmOneBased;
        end   += _apmOneBased;
dogmaphobic's avatar
dogmaphobic committed
293 294 295 296 297 298 299 300 301 302 303 304 305 306
        //-- Request these entries again
        _requestLogList((uint32_t)start, (uint32_t) end);
    } else {
        _receivedAllEntries();
    }
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::_logData(UASInterface* uas, uint32_t ofs, uint16_t id, uint8_t count, const uint8_t* data)
{
    if(!_uas || uas != _uas || !_downloadData) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
307 308
    //-- APM "Fix"
    id -= _apmOneBased;
dogmaphobic's avatar
dogmaphobic committed
309 310 311 312
    if(_downloadData->ID != id) {
        qWarning() << "Received log data for wrong log";
        return;
    }
313

314 315 316 317 318
    if ((ofs % MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) != 0) {
        qWarning() << "Ignored misaligned incoming packet @" << ofs;
        return;
    }

319 320
    bool result = false;
    uint32_t timeout_time = kTimeOutMilliseconds;
321
    if(ofs <= _downloadData->entry->size()) {
322 323 324 325 326 327 328 329 330 331 332
        const uint32_t chunk = ofs / kChunkSize;
        if (chunk != _downloadData->current_chunk) {
            qWarning() << "Ignored packet for out of order chunk" << chunk;
            return;
        }
        const uint16_t bin = (ofs - chunk*kChunkSize) / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
        if (bin >= _downloadData->chunk_table.size()) {
            qWarning() << "Out of range bin received";
        } else
            _downloadData->chunk_table.setBit(bin);
        if (_downloadData->file.pos() != ofs) {
333 334 335 336 337 338 339
            // Seek to correct position
            if (!_downloadData->file.seek(ofs)) {
                qWarning() << "Error while seeking log file offset";
                return;
            }
        }

dogmaphobic's avatar
dogmaphobic committed
340
        //-- Write chunk to file
341 342
        if(_downloadData->file.write((const char*)data, count)) {
            _downloadData->written += count;
343
            _downloadData->rate_bytes += count;
344
            if (_downloadData->elapsed.elapsed() >= kGUIRateMilliseconds) {
345 346 347 348 349
                //-- Update download rate
                qreal rrate = _downloadData->rate_bytes/(_downloadData->elapsed.elapsed()/1000.0);
                _downloadData->rate_avg = _downloadData->rate_avg*0.95 + rrate*0.05;
                _downloadData->rate_bytes = 0;

dogmaphobic's avatar
dogmaphobic committed
350
                //-- Update status
351 352 353 354
                const QString status = QString("%1 (%2/s)").arg(QGCMapEngine::bigSizeToString(_downloadData->written),
                                                                QGCMapEngine::bigSizeToString(_downloadData->rate_avg));

                _downloadData->entry->setStatus(status);
355 356 357 358 359 360
                _downloadData->elapsed.start();
            }
            result = true;
            //-- reset retries
            _retries = 0;
            //-- Reset timer
361
            _timer.start(timeout_time);
362 363
            //-- Do we have it all?
            if(_logComplete()) {
Gus Grubba's avatar
Gus Grubba committed
364
                _downloadData->entry->setStatus(QString(tr("Downloaded")));
365 366
                //-- Check for more
                _receivedAllData();
367 368 369 370 371
            } else if (_chunkComplete()) {
                _downloadData->advanceChunk();
                _requestLogData(_downloadData->ID,
                                _downloadData->current_chunk*kChunkSize,
                                _downloadData->chunk_table.size()*MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
372 373 374
            } else if (bin < _downloadData->chunk_table.size() - 1 && _downloadData->chunk_table.at(bin+1)) {
                // Likely to be grabbing fragments and got to the end of a gap
                _findMissingData();
dogmaphobic's avatar
dogmaphobic committed
375 376
            }
        } else {
377
            qWarning() << "Error while writing log file chunk";
dogmaphobic's avatar
dogmaphobic committed
378 379 380 381 382
        }
    } else {
        qWarning() << "Received log offset greater than expected";
    }
    if(!result) {
Gus Grubba's avatar
Gus Grubba committed
383
        _downloadData->entry->setStatus(QString(tr("Error")));
dogmaphobic's avatar
dogmaphobic committed
384 385 386
    }
}

387 388 389 390 391 392 393 394

//----------------------------------------------------------------------------------------
bool
LogDownloadController::_chunkComplete() const
{
    return _downloadData->chunkEquals(true);
}

dogmaphobic's avatar
dogmaphobic committed
395 396
//----------------------------------------------------------------------------------------
bool
397
LogDownloadController::_logComplete() const
dogmaphobic's avatar
dogmaphobic committed
398
{
399
    return _chunkComplete() && (_downloadData->current_chunk+1) == _downloadData->numChunks();
dogmaphobic's avatar
dogmaphobic committed
400 401 402 403 404 405 406 407 408 409
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::_receivedAllData()
{
    _timer.stop();
    //-- Anything queued up for download?
    if(_prepareLogDownload()) {
        //-- Request Log
410
        _requestLogData(_downloadData->ID, 0, _downloadData->chunk_table.size()*MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
411
        _timer.start(kTimeOutMilliseconds);
dogmaphobic's avatar
dogmaphobic committed
412 413
    } else {
        _resetSelection();
414
        _setDownloading(false);
dogmaphobic's avatar
dogmaphobic committed
415 416 417 418 419 420 421
    }
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::_findMissingData()
{
422 423 424
    if (_logComplete()) {
         _receivedAllData();
         return;
425 426
    } else if (_chunkComplete()) {
        _downloadData->advanceChunk();
dogmaphobic's avatar
dogmaphobic committed
427
    }
428 429

    if(_retries++ > 2) {
Gus Grubba's avatar
Gus Grubba committed
430
        _downloadData->entry->setStatus(QString(tr("Timed Out")));
431 432 433 434 435 436
        //-- Give up
        qWarning() << "Too many errors retreiving log data. Giving up.";
        _receivedAllData();
        return;
    }

437 438 439 440 441 442
    uint16_t start = 0, end = 0;
    const int size = _downloadData->chunk_table.size();
    for (; start < size; start++) {
        if (!_downloadData->chunk_table.testBit(start)) {
            break;
        }
dogmaphobic's avatar
dogmaphobic committed
443
    }
444 445 446 447 448 449 450 451 452 453

    for (end = start; end < size; end++) {
        if (_downloadData->chunk_table.testBit(end)) {
            break;
        }
    }

    const uint32_t pos = _downloadData->current_chunk*kChunkSize + start*MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN,
                   len = (end - start)*MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
    _requestLogData(_downloadData->ID, pos, len);
dogmaphobic's avatar
dogmaphobic committed
454 455 456 457
}

//----------------------------------------------------------------------------------------
void
458
LogDownloadController::_requestLogData(uint16_t id, uint32_t offset, uint32_t count)
dogmaphobic's avatar
dogmaphobic committed
459 460
{
    if(_vehicle) {
dogmaphobic's avatar
dogmaphobic committed
461 462
        //-- APM "Fix"
        id += _apmOneBased;
dogmaphobic's avatar
dogmaphobic committed
463 464
        qCDebug(LogDownloadLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count << ")";
        mavlink_message_t msg;
465 466 467 468 469 470 471
        mavlink_msg_log_request_data_pack_chan(
                    qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
                    qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
                    _vehicle->priorityLink()->mavlinkChannel(),
                    &msg,
                    qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->defaultComponentId(),
                    id, offset, count);
472
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
dogmaphobic's avatar
dogmaphobic committed
473 474 475 476 477 478 479 480
    }
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::refresh(void)
{
    _logEntriesModel.clear();
dogmaphobic's avatar
dogmaphobic committed
481 482
    //-- Get first 50 entries
    _requestLogList(0, 49);
dogmaphobic's avatar
dogmaphobic committed
483 484 485 486 487 488 489 490
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::_requestLogList(uint32_t start, uint32_t end)
{
    if(_vehicle && _uas) {
        qCDebug(LogDownloadLog) << "Request log entry list (" << start << "through" << end << ")";
dogmaphobic's avatar
dogmaphobic committed
491
        _setListing(true);
dogmaphobic's avatar
dogmaphobic committed
492
        mavlink_message_t msg;
493 494 495 496 497 498 499 500 501
        mavlink_msg_log_request_list_pack_chan(
                    qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
                    qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
                    _vehicle->priorityLink()->mavlinkChannel(),
                    &msg,
                    _vehicle->id(),
                    _vehicle->defaultComponentId(),
                    start,
                    end);
502
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
dogmaphobic's avatar
dogmaphobic committed
503 504
        //-- Wait 5 seconds before bitching about not getting anything
        _timer.start(5000);
dogmaphobic's avatar
dogmaphobic committed
505 506 507 508 509
    }
}

//----------------------------------------------------------------------------------------
void
510
LogDownloadController::download(QString path)
511
{
512 513 514
    QString dir = path;
#if defined(__mobile__)
    if(dir.isEmpty()) {
515
        dir = qgcApp()->toolbox()->settingsManager()->appSettings()->logSavePath();
516 517 518
    }
#else
    if(dir.isEmpty()) {
519
        dir = QGCQFileDialog::getExistingDirectory(
520
                MainWindow::instance(),
Gus Grubba's avatar
Gus Grubba committed
521
                tr("Log Download Directory"),
522
                QDir::homePath(),
523
                QGCQFileDialog::ShowDirsOnly | QGCQFileDialog::DontResolveSymlinks);
524 525
    }
#endif
526 527 528 529
    downloadToDirectory(dir);
}

void LogDownloadController::downloadToDirectory(const QString& dir)
dogmaphobic's avatar
dogmaphobic committed
530 531 532 533 534 535 536 537
{
    //-- Stop listing just in case
    _receivedAllEntries();
    //-- Reset downloads, again just in case
    if(_downloadData) {
        delete _downloadData;
        _downloadData = 0;
    }
538
    _downloadPath = dir;
dogmaphobic's avatar
dogmaphobic committed
539 540 541
    if(!_downloadPath.isEmpty()) {
        if(!_downloadPath.endsWith(QDir::separator()))
            _downloadPath += QDir::separator();
dogmaphobic's avatar
dogmaphobic committed
542 543 544 545 546 547
        //-- Iterate selected entries and shown them as waiting
        int num_logs = _logEntriesModel.count();
        for(int i = 0; i < num_logs; i++) {
            QGCLogEntry* entry = _logEntriesModel[i];
            if(entry) {
                if(entry->selected()) {
Gus Grubba's avatar
Gus Grubba committed
548
                   entry->setStatus(QString(tr("Waiting")));
dogmaphobic's avatar
dogmaphobic committed
549 550 551
                }
            }
        }
dogmaphobic's avatar
dogmaphobic committed
552
        //-- Start download process
553
        _setDownloading(true);
dogmaphobic's avatar
dogmaphobic committed
554 555 556 557
        _receivedAllData();
    }
}

558

dogmaphobic's avatar
dogmaphobic committed
559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592
//----------------------------------------------------------------------------------------
QGCLogEntry*
LogDownloadController::_getNextSelected()
{
    //-- Iterate entries and look for a selected file
    int num_logs = _logEntriesModel.count();
    for(int i = 0; i < num_logs; i++) {
        QGCLogEntry* entry = _logEntriesModel[i];
        if(entry) {
            if(entry->selected()) {
               return entry;
            }
        }
    }
    return NULL;
}

//----------------------------------------------------------------------------------------
bool
LogDownloadController::_prepareLogDownload()
{
    if(_downloadData) {
        delete _downloadData;
        _downloadData = NULL;
    }
    QGCLogEntry* entry = _getNextSelected();
    if(!entry) {
        return false;
    }
    //-- Deselect file
    entry->setSelected(false);
    emit selectionChanged();
    bool result = false;
    QString ftime;
dogmaphobic's avatar
dogmaphobic committed
593
    if(entry->time().date().year() < 2010) {
Don Gagne's avatar
Don Gagne committed
594
        ftime = tr("UnknownDate");
dogmaphobic's avatar
dogmaphobic committed
595
    } else {
Don Gagne's avatar
Don Gagne committed
596
        ftime = entry->time().toString(QStringLiteral("yyyy-M-d-hh-mm-ss"));
dogmaphobic's avatar
dogmaphobic committed
597 598
    }
    _downloadData = new LogDownloadData(entry);
599
    _downloadData->filename = QString("log_") + QString::number(entry->id()) + "_" + ftime;
600
    if (_vehicle->firmwareType() == MAV_AUTOPILOT_PX4) {
Don Gagne's avatar
Don Gagne committed
601
        QString loggerParam = QStringLiteral("SYS_LOGGER");
602 603
        if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, loggerParam) &&
                _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, loggerParam)->rawValue().toInt() == 0) {
604 605 606 607
            _downloadData->filename += ".px4log";
        } else {
            _downloadData->filename += ".ulg";
        }
608 609 610
    } else {
        _downloadData->filename += ".bin";
    }
dogmaphobic's avatar
dogmaphobic committed
611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628
    _downloadData->file.setFileName(_downloadPath + _downloadData->filename);
    //-- Append a number to the end if the filename already exists
    if (_downloadData->file.exists()){
        uint num_dups = 0;
        QStringList filename_spl = _downloadData->filename.split('.');
        do {
            num_dups +=1;
            _downloadData->file.setFileName(filename_spl[0] + '_' + QString::number(num_dups) + '.' + filename_spl[1]);
        } while( _downloadData->file.exists());
    }
    //-- Create file
    if (!_downloadData->file.open(QIODevice::WriteOnly)) {
        qWarning() << "Failed to create log file:" <<  _downloadData->filename;
    } else {
        //-- Preallocate file
        if(!_downloadData->file.resize(entry->size())) {
            qWarning() << "Failed to allocate space for log file:" <<  _downloadData->filename;
        } else {
629 630
            _downloadData->current_chunk = 0;
            _downloadData->chunk_table = QBitArray(_downloadData->chunkBins(), false);
631
            _downloadData->elapsed.start();
dogmaphobic's avatar
dogmaphobic committed
632 633 634 635 636 637 638
            result = true;
        }
    }
    if(!result) {
        if (_downloadData->file.exists()) {
            _downloadData->file.remove();
        }
Gus Grubba's avatar
Gus Grubba committed
639
        _downloadData->entry->setStatus(QString(tr("Error")));
dogmaphobic's avatar
dogmaphobic committed
640 641 642 643 644 645
        delete _downloadData;
        _downloadData = NULL;
    }
    return result;
}

646 647 648 649
//----------------------------------------------------------------------------------------
void
LogDownloadController::_setDownloading(bool active)
{
650 651 652 653 654
    if (_downloadingLogs != active) {
        _downloadingLogs = active;
        _vehicle->setConnectionLostEnabled(!active);
        emit downloadingLogsChanged();
    }
655 656
}

dogmaphobic's avatar
dogmaphobic committed
657 658 659 660
//----------------------------------------------------------------------------------------
void
LogDownloadController::_setListing(bool active)
{
661 662 663 664 665
    if (_requestingLogEntries != active) {
        _requestingLogEntries = active;
        _vehicle->setConnectionLostEnabled(!active);
        emit requestingListChanged();
    }
dogmaphobic's avatar
dogmaphobic committed
666 667
}

dogmaphobic's avatar
dogmaphobic committed
668 669 670 671 672 673
//----------------------------------------------------------------------------------------
void
LogDownloadController::eraseAll(void)
{
    if(_vehicle && _uas) {
        mavlink_message_t msg;
674 675 676 677 678 679
        mavlink_msg_log_erase_pack_chan(
                    qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
                    qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
                    _vehicle->priorityLink()->mavlinkChannel(),
                    &msg,
                    qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->defaultComponentId());
680
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
681
        refresh();
dogmaphobic's avatar
dogmaphobic committed
682 683 684 685 686 687 688 689 690 691 692
    }
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::cancel(void)
{
    if(_uas){
        _receivedAllEntries();
    }
    if(_downloadData) {
Gus Grubba's avatar
Gus Grubba committed
693
        _downloadData->entry->setStatus(QString(tr("Canceled")));
dogmaphobic's avatar
dogmaphobic committed
694 695 696 697 698 699
        if (_downloadData->file.exists()) {
            _downloadData->file.remove();
        }
        delete _downloadData;
        _downloadData = 0;
    }
dogmaphobic's avatar
dogmaphobic committed
700
    _resetSelection(true);
701
    _setDownloading(false);
dogmaphobic's avatar
dogmaphobic committed
702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732
}

//-----------------------------------------------------------------------------
QGCLogModel::QGCLogModel(QObject* parent)
    : QAbstractListModel(parent)
{

}

//-----------------------------------------------------------------------------
QGCLogEntry*
QGCLogModel::get(int index)
{
    if (index < 0 || index >= _logEntries.count()) {
        return NULL;
    }
    return _logEntries[index];
}

//-----------------------------------------------------------------------------
int
QGCLogModel::count() const
{
    return _logEntries.count();
}

//-----------------------------------------------------------------------------
void
QGCLogModel::append(QGCLogEntry* object)
{
    beginInsertRows(QModelIndex(), rowCount(), rowCount());
733
    QQmlEngine::setObjectOwnership(object, QQmlEngine::CppOwnership);
dogmaphobic's avatar
dogmaphobic committed
734 735 736 737 738 739 740 741 742 743 744 745 746
    _logEntries.append(object);
    endInsertRows();
    emit countChanged();
}

//-----------------------------------------------------------------------------
void
QGCLogModel::clear(void)
{
    if(!_logEntries.isEmpty()) {
        beginRemoveRows(QModelIndex(), 0, _logEntries.count());
        while (_logEntries.count()) {
            QGCLogEntry* entry = _logEntries.last();
747
            if(entry) entry->deleteLater();
dogmaphobic's avatar
dogmaphobic committed
748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785
            _logEntries.removeLast();
        }
        endRemoveRows();
        emit countChanged();
    }
}

//-----------------------------------------------------------------------------
QGCLogEntry*
QGCLogModel::operator[](int index)
{
    return get(index);
}

//-----------------------------------------------------------------------------
int
QGCLogModel::rowCount(const QModelIndex& /*parent*/) const
{
    return _logEntries.count();
}

//-----------------------------------------------------------------------------
QVariant
QGCLogModel::data(const QModelIndex & index, int role) const {
    if (index.row() < 0 || index.row() >= _logEntries.count())
        return QVariant();
    if (role == ObjectRole)
        return QVariant::fromValue(_logEntries[index.row()]);
    return QVariant();
}

//-----------------------------------------------------------------------------
QHash<int, QByteArray>
QGCLogModel::roleNames() const {
    QHash<int, QByteArray> roles;
    roles[ObjectRole] = "logEntry";
    return roles;
}