LogDownloadController.cc 24.9 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 24
#include "Vehicle.h"

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

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

QGC_LOGGING_CATEGORY(LogDownloadLog, "LogDownloadLog")

38 39 40 41 42 43 44 45 46 47
//-----------------------------------------------------------------------------
struct LogDownloadData {
    LogDownloadData(QGCLogEntry* entry);
    QBitArray     chunk_table;
    uint32_t      current_chunk;
    QFile         file;
    QString       filename;
    uint          ID;
    QGCLogEntry*  entry;
    uint          written;
48 49
    size_t        rate_bytes;
    qreal         rate_avg;
50 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
    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);
    }

};
78

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

}

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

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

dogmaphobic's avatar
dogmaphobic committed
108
//----------------------------------------------------------------------------------------
109 110
LogDownloadController::LogDownloadController(void)
    : _uas(NULL)
dogmaphobic's avatar
dogmaphobic committed
111 112 113 114 115
    , _downloadData(NULL)
    , _vehicle(NULL)
    , _requestingLogEntries(false)
    , _downloadingLogs(false)
    , _retries(0)
dogmaphobic's avatar
dogmaphobic committed
116
    , _apmOneBased(0)
dogmaphobic's avatar
dogmaphobic committed
117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138
{
    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)
{
139
    if(_uas) {
dogmaphobic's avatar
dogmaphobic committed
140 141 142 143 144
        _logEntriesModel.clear();
        disconnect(_uas, &UASInterface::logEntry, this, &LogDownloadController::_logEntry);
        disconnect(_uas, &UASInterface::logData,  this, &LogDownloadController::_logData);
        _uas = NULL;
    }
145 146 147 148 149 150
    _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
151 152 153 154 155 156 157 158 159 160 161
}

//----------------------------------------------------------------------------------------
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
162
    if(!_logEntriesModel.count() && num_logs > 0) {
dogmaphobic's avatar
dogmaphobic committed
163 164 165 166 167
        //-- 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
168 169 170 171 172 173
        for(int i = 0; i < num_logs; i++) {
            QGCLogEntry *entry = new QGCLogEntry(i);
            _logEntriesModel.append(entry);
        }
    }
    //-- Update this log record
174
    if(num_logs > 0) {
dogmaphobic's avatar
dogmaphobic committed
175 176 177 178 179 180 181 182 183 184 185 186
        //-- Skip if empty (APM first packet)
        if(size) {
            id -= _apmOneBased;
            if(id < _logEntriesModel.count()) {
                QGCLogEntry* entry = _logEntriesModel[id];
                entry->setSize(size);
                entry->setTime(QDateTime::fromTime_t(time_utc));
                entry->setReceived(true);
                entry->setStatus(QString("Available"));
            } else {
                qWarning() << "Received log entry for out-of-bound index:" << id;
            }
187
        }
dogmaphobic's avatar
dogmaphobic committed
188
    } else {
189 190
        //-- No logs to list
        _receivedAllEntries();
dogmaphobic's avatar
dogmaphobic committed
191 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
    }
    //-- 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
222
LogDownloadController::_resetSelection(bool canceled)
dogmaphobic's avatar
dogmaphobic committed
223 224 225 226 227
{
    int num_logs = _logEntriesModel.count();
    for(int i = 0; i < num_logs; i++) {
        QGCLogEntry* entry = _logEntriesModel[i];
        if(entry) {
dogmaphobic's avatar
dogmaphobic committed
228 229 230 231 232 233
            if(entry->selected()) {
                if(canceled) {
                    entry->setStatus(QString("Canceled"));
                }
                entry->setSelected(false);
            }
dogmaphobic's avatar
dogmaphobic committed
234 235 236 237 238 239 240 241 242 243
        }
    }
    emit selectionChanged();
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::_receivedAllEntries()
{
    _timer.stop();
dogmaphobic's avatar
dogmaphobic committed
244
    _setListing(false);
dogmaphobic's avatar
dogmaphobic committed
245 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 278 279 280 281 282 283 284 285 286 287 288
}

//----------------------------------------------------------------------------------------
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()) {
                    entry->setStatus(QString("Error"));
                }
            }
            //-- 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
289 290 291
        //-- APM "Fix"
        start += _apmOneBased;
        end   += _apmOneBased;
dogmaphobic's avatar
dogmaphobic committed
292 293 294 295 296 297 298 299 300 301 302 303 304 305
        //-- 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
306 307
    //-- APM "Fix"
    id -= _apmOneBased;
dogmaphobic's avatar
dogmaphobic committed
308 309 310 311
    if(_downloadData->ID != id) {
        qWarning() << "Received log data for wrong log";
        return;
    }
312

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

318 319
    bool result = false;
    uint32_t timeout_time = kTimeOutMilliseconds;
320
    if(ofs <= _downloadData->entry->size()) {
321 322 323 324 325 326 327 328 329 330 331
        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) {
332 333 334 335 336 337 338
            // Seek to correct position
            if (!_downloadData->file.seek(ofs)) {
                qWarning() << "Error while seeking log file offset";
                return;
            }
        }

dogmaphobic's avatar
dogmaphobic committed
339
        //-- Write chunk to file
340 341
        if(_downloadData->file.write((const char*)data, count)) {
            _downloadData->written += count;
342
            _downloadData->rate_bytes += count;
343
            if (_downloadData->elapsed.elapsed() >= kGUIRateMilliseconds) {
344 345 346 347 348
                //-- 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
349
                //-- Update status
350 351 352 353
                const QString status = QString("%1 (%2/s)").arg(QGCMapEngine::bigSizeToString(_downloadData->written),
                                                                QGCMapEngine::bigSizeToString(_downloadData->rate_avg));

                _downloadData->entry->setStatus(status);
354 355 356 357 358 359
                _downloadData->elapsed.start();
            }
            result = true;
            //-- reset retries
            _retries = 0;
            //-- Reset timer
360
            _timer.start(timeout_time);
361 362 363 364 365
            //-- Do we have it all?
            if(_logComplete()) {
                _downloadData->entry->setStatus(QString("Downloaded"));
                //-- Check for more
                _receivedAllData();
366 367 368 369 370
            } else if (_chunkComplete()) {
                _downloadData->advanceChunk();
                _requestLogData(_downloadData->ID,
                                _downloadData->current_chunk*kChunkSize,
                                _downloadData->chunk_table.size()*MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
371 372 373
            } 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
374 375
            }
        } else {
376
            qWarning() << "Error while writing log file chunk";
dogmaphobic's avatar
dogmaphobic committed
377 378 379 380 381 382 383 384 385
        }
    } else {
        qWarning() << "Received log offset greater than expected";
    }
    if(!result) {
        _downloadData->entry->setStatus(QString("Error"));
    }
}

386 387 388 389 390 391 392 393

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

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

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

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

    if(_retries++ > 2) {
        _downloadData->entry->setStatus(QString("Timed Out"));
        //-- Give up
        qWarning() << "Too many errors retreiving log data. Giving up.";
        _receivedAllData();
        return;
    }

435 436 437 438 439 440
    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
441
    }
442 443 444 445 446 447 448 449 450 451

    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
452 453 454 455 456 457 458
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::_requestLogData(uint8_t id, uint32_t offset, uint32_t count)
{
    if(_vehicle) {
dogmaphobic's avatar
dogmaphobic committed
459 460
        //-- APM "Fix"
        id += _apmOneBased;
dogmaphobic's avatar
dogmaphobic committed
461 462
        qCDebug(LogDownloadLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count << ")";
        mavlink_message_t msg;
463 464 465 466 467 468 469
        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);
470
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
dogmaphobic's avatar
dogmaphobic committed
471 472 473 474 475 476 477 478
    }
}

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

//----------------------------------------------------------------------------------------
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
489
        _setListing(true);
dogmaphobic's avatar
dogmaphobic committed
490
        mavlink_message_t msg;
491 492 493 494 495 496 497 498 499
        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);
500
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
dogmaphobic's avatar
dogmaphobic committed
501 502
        //-- Wait 5 seconds before bitching about not getting anything
        _timer.start(5000);
dogmaphobic's avatar
dogmaphobic committed
503 504 505 506 507
    }
}

//----------------------------------------------------------------------------------------
void
508
LogDownloadController::download(QString path)
509
{
510 511 512 513 514 515 516
    QString dir = path;
#if defined(__mobile__)
    if(dir.isEmpty()) {
        dir = QDir::homePath();
    }
#else
    if(dir.isEmpty()) {
517
        dir = QGCQFileDialog::getExistingDirectory(
518 519 520
                MainWindow::instance(),
                "Log Download Directory",
                QDir::homePath(),
521
                QGCQFileDialog::ShowDirsOnly | QGCQFileDialog::DontResolveSymlinks);
522 523
    }
#endif
524 525 526 527
    downloadToDirectory(dir);
}

void LogDownloadController::downloadToDirectory(const QString& dir)
dogmaphobic's avatar
dogmaphobic committed
528 529 530 531 532 533 534 535
{
    //-- Stop listing just in case
    _receivedAllEntries();
    //-- Reset downloads, again just in case
    if(_downloadData) {
        delete _downloadData;
        _downloadData = 0;
    }
536
    _downloadPath = dir;
dogmaphobic's avatar
dogmaphobic committed
537 538 539
    if(!_downloadPath.isEmpty()) {
        if(!_downloadPath.endsWith(QDir::separator()))
            _downloadPath += QDir::separator();
dogmaphobic's avatar
dogmaphobic committed
540 541 542 543 544 545 546 547 548 549
        //-- 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()) {
                   entry->setStatus(QString("Waiting"));
                }
            }
        }
dogmaphobic's avatar
dogmaphobic committed
550
        //-- Start download process
551
        _setDownloading(true);
dogmaphobic's avatar
dogmaphobic committed
552 553 554 555
        _receivedAllData();
    }
}

556

dogmaphobic's avatar
dogmaphobic committed
557 558 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
//----------------------------------------------------------------------------------------
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
591
    if(entry->time().date().year() < 2010) {
dogmaphobic's avatar
dogmaphobic committed
592 593 594 595 596
        ftime = "UnknownDate";
    } else {
        ftime = entry->time().toString("yyyy-M-d-hh-mm-ss");
    }
    _downloadData = new LogDownloadData(entry);
597
    _downloadData->filename = QString("log_") + QString::number(entry->id()) + "_" + ftime;
598 599 600 601 602 603 604 605
    if (_vehicle->firmwareType() == MAV_AUTOPILOT_PX4) {

        // This is a stopgap and should be removed once log file types are properly supported by the log download protocol
        if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "SYS_LOGGER")->rawValue().toInt() == 0) {
            _downloadData->filename += ".px4log";
        } else {
            _downloadData->filename += ".ulg";
        }
606 607 608
    } else {
        _downloadData->filename += ".bin";
    }
dogmaphobic's avatar
dogmaphobic committed
609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626
    _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 {
627 628
            _downloadData->current_chunk = 0;
            _downloadData->chunk_table = QBitArray(_downloadData->chunkBins(), false);
629
            _downloadData->elapsed.start();
dogmaphobic's avatar
dogmaphobic committed
630 631 632 633 634 635 636 637 638 639 640 641 642 643
            result = true;
        }
    }
    if(!result) {
        if (_downloadData->file.exists()) {
            _downloadData->file.remove();
        }
        _downloadData->entry->setStatus(QString("Error"));
        delete _downloadData;
        _downloadData = NULL;
    }
    return result;
}

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

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

dogmaphobic's avatar
dogmaphobic committed
666 667 668 669 670 671
//----------------------------------------------------------------------------------------
void
LogDownloadController::eraseAll(void)
{
    if(_vehicle && _uas) {
        mavlink_message_t msg;
672 673 674 675 676 677
        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());
678
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
679
        refresh();
dogmaphobic's avatar
dogmaphobic committed
680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697
    }
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::cancel(void)
{
    if(_uas){
        _receivedAllEntries();
    }
    if(_downloadData) {
        _downloadData->entry->setStatus(QString("Canceled"));
        if (_downloadData->file.exists()) {
            _downloadData->file.remove();
        }
        delete _downloadData;
        _downloadData = 0;
    }
dogmaphobic's avatar
dogmaphobic committed
698
    _resetSelection(true);
699
    _setDownloading(false);
dogmaphobic's avatar
dogmaphobic committed
700 701 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
}

//-----------------------------------------------------------------------------
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());
731
    QQmlEngine::setObjectOwnership(object, QQmlEngine::CppOwnership);
dogmaphobic's avatar
dogmaphobic committed
732 733 734 735 736 737 738 739 740 741 742 743 744
    _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();
745
            if(entry) entry->deleteLater();
dogmaphobic's avatar
dogmaphobic committed
746 747 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
            _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;
}