From c5e4c183795c27f8be0007ce3ef87fd56f7e4834 Mon Sep 17 00:00:00 2001
From: dogmaphobic <mavlink@grubba.com>
Date: Wed, 6 Jan 2016 09:52:03 -0500
Subject: [PATCH] APM Log Download "Fix"

---
 src/ViewWidgets/LogDownload.qml          |  2 +-
 src/ViewWidgets/LogDownloadController.cc | 58 ++++++++++++++++++------
 src/ViewWidgets/LogDownloadController.h  |  3 +-
 3 files changed, 48 insertions(+), 15 deletions(-)

diff --git a/src/ViewWidgets/LogDownload.qml b/src/ViewWidgets/LogDownload.qml
index e6092351ee..5dc2b30238 100644
--- a/src/ViewWidgets/LogDownload.qml
+++ b/src/ViewWidgets/LogDownload.qml
@@ -94,7 +94,7 @@ QGCView {
                             //-- Have we received this entry already?
                             if(controller.model.get(styleData.row).received) {
                                 var d = controller.model.get(styleData.row).time
-                                if(d.getUTCFullYear() < 1980)
+                                if(d.getUTCFullYear() < 2010)
                                     return "Date Unknown"
                                 else
                                     return d.toLocaleString()
diff --git a/src/ViewWidgets/LogDownloadController.cc b/src/ViewWidgets/LogDownloadController.cc
index 445d946eed..6fb40a10d0 100644
--- a/src/ViewWidgets/LogDownloadController.cc
+++ b/src/ViewWidgets/LogDownloadController.cc
@@ -67,6 +67,7 @@ LogDownloadController::LogDownloadController(void)
     , _requestingLogEntries(false)
     , _downloadingLogs(false)
     , _retries(0)
+    , _apmOneBased(0)
 {
     MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager();
     connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &LogDownloadController::_setActiveVehicle);
@@ -114,6 +115,11 @@ LogDownloadController::_logEntry(UASInterface* uas, uint32_t time_utc, uint32_t
     }
     //-- If this is the first, pre-fill it
     if(!_logEntriesModel.count() && num_logs > 0) {
+        //-- 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;
+        }
         for(int i = 0; i < num_logs; i++) {
             QGCLogEntry *entry = new QGCLogEntry(i);
             _logEntriesModel.append(entry);
@@ -121,14 +127,18 @@ LogDownloadController::_logEntry(UASInterface* uas, uint32_t time_utc, uint32_t
     }
     //-- Update this log record
     if(num_logs > 0) {
-        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;
+        //-- 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;
+            }
         }
     } else {
         //-- No logs to list
@@ -164,13 +174,18 @@ LogDownloadController::_entriesComplete()
 
 //----------------------------------------------------------------------------------------
 void
-LogDownloadController::_resetSelection()
+LogDownloadController::_resetSelection(bool canceled)
 {
     int num_logs = _logEntriesModel.count();
     for(int i = 0; i < num_logs; i++) {
         QGCLogEntry* entry = _logEntriesModel[i];
         if(entry) {
-            entry->setSelected(false);
+            if(entry->selected()) {
+                if(canceled) {
+                    entry->setStatus(QString("Canceled"));
+                }
+                entry->setSelected(false);
+            }
         }
     }
     emit selectionChanged();
@@ -227,6 +242,9 @@ LogDownloadController::_findMissingEntries()
         if(end < 0) {
             end = start;
         }
+        //-- APM "Fix"
+        start += _apmOneBased;
+        end   += _apmOneBased;
         //-- Request these entries again
         _requestLogList((uint32_t)start, (uint32_t) end);
     } else {
@@ -241,6 +259,8 @@ LogDownloadController::_logData(UASInterface* uas, uint32_t ofs, uint16_t id, ui
     if(!_uas || uas != _uas || !_downloadData) {
         return;
     }
+    //-- APM "Fix"
+    id -= _apmOneBased;
     if(_downloadData->ID != id) {
         qWarning() << "Received log data for wrong log";
         return;
@@ -360,6 +380,8 @@ void
 LogDownloadController::_requestLogData(uint8_t id, uint32_t offset, uint32_t count)
 {
     if(_vehicle) {
+        //-- APM "Fix"
+        id += _apmOneBased;
         qCDebug(LogDownloadLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count << ")";
         mavlink_message_t msg;
         mavlink_msg_log_request_data_pack(
@@ -423,6 +445,16 @@ LogDownloadController::download(void)
     if(!_downloadPath.isEmpty()) {
         if(!_downloadPath.endsWith(QDir::separator()))
             _downloadPath += QDir::separator();
+        //-- 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"));
+                }
+            }
+        }
         //-- Start download process
         _downloadingLogs = true;
         emit downloadingLogsChanged();
@@ -464,13 +496,13 @@ LogDownloadController::_prepareLogDownload()
     emit selectionChanged();
     bool result = false;
     QString ftime;
-    if(entry->time().date().year() < 1980) {
+    if(entry->time().date().year() < 2010) {
         ftime = "UnknownDate";
     } else {
         ftime = entry->time().toString("yyyy-M-d-hh-mm-ss");
     }
     _downloadData = new LogDownloadData(entry);
-    _downloadData->filename = QString("log_") + QString::number(entry->id()) + "_" + ftime + ".txt";
+    _downloadData->filename = QString("log_") + QString::number(entry->id()) + "_" + ftime + ".mavlink";
     _downloadData->file.setFileName(_downloadPath + _downloadData->filename);
     //-- Append a number to the end if the filename already exists
     if (_downloadData->file.exists()){
@@ -539,7 +571,7 @@ LogDownloadController::cancel(void)
         delete _downloadData;
         _downloadData = 0;
     }
-    _resetSelection();
+    _resetSelection(true);
     _downloadingLogs = false;
     emit downloadingLogsChanged();
 }
diff --git a/src/ViewWidgets/LogDownloadController.h b/src/ViewWidgets/LogDownloadController.h
index 3c29836f6a..21010acc13 100644
--- a/src/ViewWidgets/LogDownloadController.h
+++ b/src/ViewWidgets/LogDownloadController.h
@@ -171,7 +171,7 @@ private:
     void _findMissingEntries();
     void _receivedAllEntries();
     void _receivedAllData   ();
-    void _resetSelection    ();
+    void _resetSelection    (bool canceled = false);
     void _findMissingData   ();
     void _requestLogList    (uint32_t start = 0, uint32_t end = 0xFFFF);
     void _requestLogData    (uint8_t id, uint32_t offset = 0, uint32_t count = 0xFFFFFFFF);
@@ -187,6 +187,7 @@ private:
     bool                _requestingLogEntries;
     bool                _downloadingLogs;
     int                 _retries;
+    int                 _apmOneBased;
     QString             _downloadPath;
 };
 
-- 
GitLab