LogDownloadController.cc 25 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8
 *
 * 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 14 15 16


#include "LogDownloadController.h"
#include "MultiVehicleManager.h"
#include "QGCMAVLink.h"
#include "UAS.h"
#include "QGCApplication.h"
#include "QGCToolbox.h"
17
#include "QGCMapEngine.h"
18
#include "ParameterManager.h"
dogmaphobic's avatar
dogmaphobic committed
19
#include "Vehicle.h"
20
#include "SettingsManager.h"
dogmaphobic's avatar
dogmaphobic committed
21

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

#define kTimeOutMilliseconds 500
29
#define kGUIRateMilliseconds 17
dogmaphobic's avatar
dogmaphobic committed
30
#define kTableBins           512
31
#define kChunkSize           (kTableBins * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN)
dogmaphobic's avatar
dogmaphobic committed
32 33 34

QGC_LOGGING_CATEGORY(LogDownloadLog, "LogDownloadLog")

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

};
75

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

}

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

98 99 100 101
//----------------------------------------------------------------------------------------
QString
QGCLogEntry::sizeStr() const
{
102
    return QGCMapEngine::bigSizeToString(_logSize);
103 104
}

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

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

//----------------------------------------------------------------------------------------
void
LogDownloadController::_receivedAllEntries()
{
    _timer.stop();
dogmaphobic's avatar
dogmaphobic committed
241
    _setListing(false);
dogmaphobic's avatar
dogmaphobic committed
242 243 244 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
}

//----------------------------------------------------------------------------------------
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()) {
274
                    entry->setStatus(tr("Error"));
dogmaphobic's avatar
dogmaphobic committed
275 276 277 278 279 280 281 282 283 284 285
                }
            }
            //-- 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
286 287 288
        //-- APM "Fix"
        start += _apmOneBased;
        end   += _apmOneBased;
dogmaphobic's avatar
dogmaphobic committed
289 290 291 292 293 294 295 296 297 298 299 300 301 302
        //-- 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
303 304
    //-- APM "Fix"
    id -= _apmOneBased;
dogmaphobic's avatar
dogmaphobic committed
305 306 307 308
    if(_downloadData->ID != id) {
        qWarning() << "Received log data for wrong log";
        return;
    }
309

310 311 312 313 314
    if ((ofs % MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) != 0) {
        qWarning() << "Ignored misaligned incoming packet @" << ofs;
        return;
    }

315 316
    bool result = false;
    uint32_t timeout_time = kTimeOutMilliseconds;
317
    if(ofs <= _downloadData->entry->size()) {
318 319
        const uint32_t chunk = ofs / kChunkSize;
        if (chunk != _downloadData->current_chunk) {
DonLakeFlyer's avatar
DonLakeFlyer committed
320
            qWarning() << "Ignored packet for out of order chunk actual:expected" << chunk << _downloadData->current_chunk;
321 322 323 324 325 326 327 328
            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) {
329 330 331 332 333 334 335
            // Seek to correct position
            if (!_downloadData->file.seek(ofs)) {
                qWarning() << "Error while seeking log file offset";
                return;
            }
        }

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

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

383 384 385 386 387 388 389 390

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

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

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

//----------------------------------------------------------------------------------------
void
LogDownloadController::_findMissingData()
{
418 419 420
    if (_logComplete()) {
         _receivedAllData();
         return;
421 422
    } else if (_chunkComplete()) {
        _downloadData->advanceChunk();
dogmaphobic's avatar
dogmaphobic committed
423
    }
424 425

    if(_retries++ > 2) {
426
        _downloadData->entry->setStatus(tr("Timed Out"));
427 428 429 430 431 432
        //-- Give up
        qWarning() << "Too many errors retreiving log data. Giving up.";
        _receivedAllData();
        return;
    }

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

    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
450 451 452 453
}

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

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

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

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

void LogDownloadController::downloadToDirectory(const QString& dir)
dogmaphobic's avatar
dogmaphobic committed
526 527 528 529
{
    //-- Stop listing just in case
    _receivedAllEntries();
    //-- Reset downloads, again just in case
530 531 532
    delete _downloadData;
    _downloadData = nullptr;

533
    _downloadPath = dir;
dogmaphobic's avatar
dogmaphobic committed
534 535 536
    if(!_downloadPath.isEmpty()) {
        if(!_downloadPath.endsWith(QDir::separator()))
            _downloadPath += QDir::separator();
dogmaphobic's avatar
dogmaphobic committed
537 538 539 540 541 542
        //-- 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()) {
543
                   entry->setStatus(tr("Waiting"));
dogmaphobic's avatar
dogmaphobic committed
544 545 546
                }
            }
        }
dogmaphobic's avatar
dogmaphobic committed
547
        //-- Start download process
548
        _setDownloading(true);
dogmaphobic's avatar
dogmaphobic committed
549 550 551 552
        _receivedAllData();
    }
}

553

dogmaphobic's avatar
dogmaphobic committed
554 555 556 557 558 559 560 561 562 563 564 565 566 567
//----------------------------------------------------------------------------------------
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;
            }
        }
    }
568
    return nullptr;
dogmaphobic's avatar
dogmaphobic committed
569 570 571 572 573 574
}

//----------------------------------------------------------------------------------------
bool
LogDownloadController::_prepareLogDownload()
{
575 576 577
    delete _downloadData;
    _downloadData = nullptr;

dogmaphobic's avatar
dogmaphobic committed
578 579 580 581 582 583 584 585 586
    QGCLogEntry* entry = _getNextSelected();
    if(!entry) {
        return false;
    }
    //-- Deselect file
    entry->setSelected(false);
    emit selectionChanged();
    bool result = false;
    QString ftime;
dogmaphobic's avatar
dogmaphobic committed
587
    if(entry->time().date().year() < 2010) {
Don Gagne's avatar
Don Gagne committed
588
        ftime = tr("UnknownDate");
dogmaphobic's avatar
dogmaphobic committed
589
    } else {
Don Gagne's avatar
Don Gagne committed
590
        ftime = entry->time().toString(QStringLiteral("yyyy-M-d-hh-mm-ss"));
dogmaphobic's avatar
dogmaphobic committed
591 592
    }
    _downloadData = new LogDownloadData(entry);
593
    _downloadData->filename = QString("log_") + QString::number(entry->id()) + "_" + ftime;
594
    if (_vehicle->firmwareType() == MAV_AUTOPILOT_PX4) {
Don Gagne's avatar
Don Gagne committed
595
        QString loggerParam = QStringLiteral("SYS_LOGGER");
596 597
        if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, loggerParam) &&
                _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, loggerParam)->rawValue().toInt() == 0) {
598 599 600 601
            _downloadData->filename += ".px4log";
        } else {
            _downloadData->filename += ".ulg";
        }
602 603 604
    } else {
        _downloadData->filename += ".bin";
    }
dogmaphobic's avatar
dogmaphobic committed
605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622
    _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 {
623 624
            _downloadData->current_chunk = 0;
            _downloadData->chunk_table = QBitArray(_downloadData->chunkBins(), false);
625
            _downloadData->elapsed.start();
dogmaphobic's avatar
dogmaphobic committed
626 627 628 629 630 631 632
            result = true;
        }
    }
    if(!result) {
        if (_downloadData->file.exists()) {
            _downloadData->file.remove();
        }
633
        _downloadData->entry->setStatus(tr("Error"));
dogmaphobic's avatar
dogmaphobic committed
634
        delete _downloadData;
635
        _downloadData = nullptr;
dogmaphobic's avatar
dogmaphobic committed
636 637 638 639
    }
    return result;
}

640 641 642 643
//----------------------------------------------------------------------------------------
void
LogDownloadController::_setDownloading(bool active)
{
644 645 646 647 648
    if (_downloadingLogs != active) {
        _downloadingLogs = active;
        _vehicle->setConnectionLostEnabled(!active);
        emit downloadingLogsChanged();
    }
649 650
}

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

dogmaphobic's avatar
dogmaphobic committed
662 663 664 665 666 667
//----------------------------------------------------------------------------------------
void
LogDownloadController::eraseAll(void)
{
    if(_vehicle && _uas) {
        mavlink_message_t msg;
668 669 670 671 672 673
        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());
674
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
675
        refresh();
dogmaphobic's avatar
dogmaphobic committed
676 677 678 679 680 681 682 683 684 685 686
    }
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::cancel(void)
{
    if(_uas){
        _receivedAllEntries();
    }
    if(_downloadData) {
687
        _downloadData->entry->setStatus(tr("Canceled"));
dogmaphobic's avatar
dogmaphobic committed
688 689 690 691 692 693
        if (_downloadData->file.exists()) {
            _downloadData->file.remove();
        }
        delete _downloadData;
        _downloadData = 0;
    }
dogmaphobic's avatar
dogmaphobic committed
694
    _resetSelection(true);
695
    _setDownloading(false);
dogmaphobic's avatar
dogmaphobic committed
696 697 698 699 700 701 702 703 704 705 706 707 708 709
}

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

}

//-----------------------------------------------------------------------------
QGCLogEntry*
QGCLogModel::get(int index)
{
    if (index < 0 || index >= _logEntries.count()) {
710
        return nullptr;
dogmaphobic's avatar
dogmaphobic committed
711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726
    }
    return _logEntries[index];
}

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

//-----------------------------------------------------------------------------
void
QGCLogModel::append(QGCLogEntry* object)
{
    beginInsertRows(QModelIndex(), rowCount(), rowCount());
727
    QQmlEngine::setObjectOwnership(object, QQmlEngine::CppOwnership);
dogmaphobic's avatar
dogmaphobic committed
728 729 730 731 732 733 734 735 736 737 738 739 740
    _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();
741
            if(entry) entry->deleteLater();
dogmaphobic's avatar
dogmaphobic committed
742 743 744 745 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
            _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;
}