LogDownloadController.cc 20.7 KB
Newer Older
dogmaphobic's avatar
dogmaphobic committed
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33
/*=====================================================================

 QGroundControl Open Source Ground Control Station

 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>

 This file is part of the QGROUNDCONTROL project

 QGROUNDCONTROL is free software: you can redistribute it and/or modify
 it under the terms of the GNU General Public License as published by
 the Free Software Foundation, either version 3 of the License, or
 (at your option) any later version.

 QGROUNDCONTROL is distributed in the hope that it will be useful,
 but WITHOUT ANY WARRANTY; without even the implied warranty of
 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 GNU General Public License for more details.

 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.

 ======================================================================*/

#include "LogDownloadController.h"
#include "MultiVehicleManager.h"
#include "QGCMAVLink.h"
#include "QGCFileDialog.h"
#include "UAS.h"
#include "QGCApplication.h"
#include "QGCToolbox.h"
#include "Vehicle.h"
#include "MainWindow.h"

dogmaphobic's avatar
dogmaphobic committed
34
#include <QDebug>
dogmaphobic's avatar
dogmaphobic committed
35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69
#include <QSettings>
#include <QUrl>

#define kTimeOutMilliseconds 500

QGC_LOGGING_CATEGORY(LogDownloadLog, "LogDownloadLog")

//----------------------------------------------------------------------------------------
LogDownloadData::LogDownloadData(QGCLogEntry* entry_)
    : ID(entry_->id())
    , entry(entry_)
    , written(0)
{

}

//----------------------------------------------------------------------------------------
QGCLogEntry:: QGCLogEntry(uint logId, const QDateTime& dateTime, uint logSize, bool received)
    : _logID(logId)
    , _logSize(logSize)
    , _logTimeUTC(dateTime)
    , _received(received)
    , _selected(false)
{
    _status = "Pending";
}

//----------------------------------------------------------------------------------------
LogDownloadController::LogDownloadController(void)
    : _uas(NULL)
    , _downloadData(NULL)
    , _vehicle(NULL)
    , _requestingLogEntries(false)
    , _downloadingLogs(false)
    , _retries(0)
dogmaphobic's avatar
dogmaphobic committed
70
    , _apmOneBased(0)
dogmaphobic's avatar
dogmaphobic committed
71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116
{
    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)
{
    if((_uas && vehicle && _uas == vehicle->uas()) || !vehicle ) {
        return;
    }
    _vehicle = vehicle;
    if (_uas) {
        _logEntriesModel.clear();
        disconnect(_uas, &UASInterface::logEntry, this, &LogDownloadController::_logEntry);
        disconnect(_uas, &UASInterface::logData,  this, &LogDownloadController::_logData);
        _uas = NULL;
    }
    _uas = vehicle->uas();
    connect(_uas, &UASInterface::logEntry, this, &LogDownloadController::_logEntry);
    connect(_uas, &UASInterface::logData,  this, &LogDownloadController::_logData);
}

//----------------------------------------------------------------------------------------
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
117
    if(!_logEntriesModel.count() && num_logs > 0) {
dogmaphobic's avatar
dogmaphobic committed
118 119 120 121 122
        //-- 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
123 124 125 126 127 128
        for(int i = 0; i < num_logs; i++) {
            QGCLogEntry *entry = new QGCLogEntry(i);
            _logEntriesModel.append(entry);
        }
    }
    //-- Update this log record
129
    if(num_logs > 0) {
dogmaphobic's avatar
dogmaphobic committed
130 131 132 133 134 135 136 137 138 139 140 141
        //-- 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;
            }
142
        }
dogmaphobic's avatar
dogmaphobic committed
143
    } else {
144 145
        //-- No logs to list
        _receivedAllEntries();
dogmaphobic's avatar
dogmaphobic committed
146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176
    }
    //-- 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
177
LogDownloadController::_resetSelection(bool canceled)
dogmaphobic's avatar
dogmaphobic committed
178 179 180 181 182
{
    int num_logs = _logEntriesModel.count();
    for(int i = 0; i < num_logs; i++) {
        QGCLogEntry* entry = _logEntriesModel[i];
        if(entry) {
dogmaphobic's avatar
dogmaphobic committed
183 184 185 186 187 188
            if(entry->selected()) {
                if(canceled) {
                    entry->setStatus(QString("Canceled"));
                }
                entry->setSelected(false);
            }
dogmaphobic's avatar
dogmaphobic committed
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 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244
        }
    }
    emit selectionChanged();
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::_receivedAllEntries()
{
    _timer.stop();
    _requestingLogEntries = false;
    emit requestingListChanged();
}

//----------------------------------------------------------------------------------------
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
245 246 247
        //-- APM "Fix"
        start += _apmOneBased;
        end   += _apmOneBased;
dogmaphobic's avatar
dogmaphobic committed
248 249 250 251 252 253 254 255 256 257 258 259 260 261
        //-- 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
262 263
    //-- APM "Fix"
    id -= _apmOneBased;
dogmaphobic's avatar
dogmaphobic committed
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 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382
    if(_downloadData->ID != id) {
        qWarning() << "Received log data for wrong log";
        return;
    }
    bool result = false;
    //-- Find offset table entry
    uint o_index = ofs / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
    if(o_index <= (uint)_downloadData->offsets.count()) {
        _downloadData->offsets[o_index] = count;
        //-- Write chunk to file
        if(_downloadData->file.seek(ofs)) {
            if(_downloadData->file.write((const char*)data, count)) {
                _downloadData->written += count;
                //-- Update status
                _downloadData->entry->setStatus(QString::number(_downloadData->written));
                result = true;
                //-- reset retries
                _retries = 0;
                //-- Reset timer
                _timer.start(kTimeOutMilliseconds);
                //-- Do we have it all?
                if(_logComplete()) {
                    _downloadData->entry->setStatus(QString("Downloaded"));
                    //-- Check for more
                    _receivedAllData();
                }
            } else {
                qWarning() << "Error while writing log file chunk";
            }
        } else {
            qWarning() << "Error while seeking log file offset";
        }
    } else {
        qWarning() << "Received log offset greater than expected";
    }
    if(!result) {
        _downloadData->entry->setStatus(QString("Error"));
    }
}

//----------------------------------------------------------------------------------------
bool
LogDownloadController::_logComplete()
{
    //-- Iterate entries and look for a gap
    int num_ofs = _downloadData->offsets.count();
    for(int i = 0; i < num_ofs; i++) {
        if(_downloadData->offsets[i] == 0) {
           return false;
        }
    }
    return true;
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::_receivedAllData()
{
    _timer.stop();
    //-- Anything queued up for download?
    if(_prepareLogDownload()) {
        //-- Request Log
        _requestLogData(_downloadData->ID, 0, _downloadData->entry->size());
    } else {
        _resetSelection();
        _downloadingLogs = false;
        emit downloadingLogsChanged();
    }
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::_findMissingData()
{
    int start = -1;
    int end   = -1;
    int num_ofs = _downloadData->offsets.count();
    //-- Iterate offsets and look for a gap
    for(int i = 0; i < num_ofs; i++) {
        if(_downloadData->offsets[i] == 0) {
            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) {
            _downloadData->entry->setStatus(QString("Timed Out"));
            //-- Give up
            qWarning() << "Too many errors retreiving log data. Giving up.";
            _receivedAllData();
            return;
        }
        //-- Is it a sequence or just one entry?
        if(end < 0) {
            end = start;
        }
        //-- Request these log chunks again
        _requestLogData(
            _downloadData->ID,
            (uint32_t)(start * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN),
            (uint32_t)((end - start + 1) * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN));
    } else {
        _receivedAllData();
    }
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::_requestLogData(uint8_t id, uint32_t offset, uint32_t count)
{
    if(_vehicle) {
dogmaphobic's avatar
dogmaphobic committed
383 384
        //-- APM "Fix"
        id += _apmOneBased;
dogmaphobic's avatar
dogmaphobic committed
385 386 387 388 389 390 391 392
        qCDebug(LogDownloadLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count << ")";
        mavlink_message_t msg;
        mavlink_msg_log_request_data_pack(
            qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
            qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
            &msg,
            qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), MAV_COMP_ID_ALL,
            id, offset, count);
393
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
dogmaphobic's avatar
dogmaphobic committed
394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421
    }
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::refresh(void)
{
    _logEntriesModel.clear();
    _requestLogList();
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::_requestLogList(uint32_t start, uint32_t end)
{
    if(_vehicle && _uas) {
        qCDebug(LogDownloadLog) << "Request log entry list (" << start << "through" << end << ")";
        _requestingLogEntries = true;
        emit requestingListChanged();
        mavlink_message_t msg;
        mavlink_msg_log_request_list_pack(
            qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
            qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
            &msg,
            _vehicle->id(),
            MAV_COMP_ID_ALL,
            start,
            end);
422
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
dogmaphobic's avatar
dogmaphobic committed
423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447
        //-- Wait 2 seconds before bitching about not getting anything
        _timer.start(2000);
    }
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::download(void)
{
    //-- Stop listing just in case
    _receivedAllEntries();
    //-- Reset downloads, again just in case
    if(_downloadData) {
        delete _downloadData;
        _downloadData = 0;
    }
    _downloadPath.clear();
    _downloadPath = QGCFileDialog::getExistingDirectory(
        MainWindow::instance(),
        "Log Download Directory",
        QDir::homePath(),
        QGCFileDialog::ShowDirsOnly | QGCFileDialog::DontResolveSymlinks);
    if(!_downloadPath.isEmpty()) {
        if(!_downloadPath.endsWith(QDir::separator()))
            _downloadPath += QDir::separator();
dogmaphobic's avatar
dogmaphobic committed
448 449 450 451 452 453 454 455 456 457
        //-- 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
458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498
        //-- Start download process
        _downloadingLogs = true;
        emit downloadingLogsChanged();
        _receivedAllData();
    }
}

//----------------------------------------------------------------------------------------
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
499
    if(entry->time().date().year() < 2010) {
dogmaphobic's avatar
dogmaphobic committed
500 501 502 503 504
        ftime = "UnknownDate";
    } else {
        ftime = entry->time().toString("yyyy-M-d-hh-mm-ss");
    }
    _downloadData = new LogDownloadData(entry);
505 506 507 508 509 510
    _downloadData->filename = QString("log_") + QString::number(entry->id()) + "_" + ftime;
    if(_vehicle->firmwareType() == MAV_AUTOPILOT_PX4) {
        _downloadData->filename += ".px4log";
    } else {
        _downloadData->filename += ".bin";
    }
dogmaphobic's avatar
dogmaphobic committed
511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558
    _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 {
            //-- Prepare Offset Table
            uint o_count = (uint)ceil(entry->size() / (double)MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
            for(uint i = 0; i < o_count; i++) {
                _downloadData->offsets.append(0);
            }
            result = true;
        }
    }
    if(!result) {
        if (_downloadData->file.exists()) {
            _downloadData->file.remove();
        }
        _downloadData->entry->setStatus(QString("Error"));
        delete _downloadData;
        _downloadData = NULL;
    }
    return result;
}

//----------------------------------------------------------------------------------------
void
LogDownloadController::eraseAll(void)
{
    if(_vehicle && _uas) {
        mavlink_message_t msg;
        mavlink_msg_log_erase_pack(
            qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
            qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
            &msg,
            qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), MAV_COMP_ID_ALL);
559
        _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
560
        refresh();
dogmaphobic's avatar
dogmaphobic committed
561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578
    }
}

//----------------------------------------------------------------------------------------
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
579
    _resetSelection(true);
dogmaphobic's avatar
dogmaphobic committed
580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664
    _downloadingLogs = false;
    emit downloadingLogsChanged();
}

//-----------------------------------------------------------------------------
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());
    _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();
            if(entry) delete entry;
            _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;
}