From fe8ca32213d0f94a74a413afb3a4e77127666269 Mon Sep 17 00:00:00 2001 From: Gus Grubba Date: Wed, 17 May 2017 00:10:10 -0400 Subject: [PATCH] Allow (mobile) plugins to define telemetry logs. --- src/QGCApplication.cc | 58 +++++++++++++++++++++++-------------- src/QGCApplication.h | 2 -- src/api/QGCCorePlugin.cc | 15 ++++++++-- src/comm/MAVLinkProtocol.cc | 48 ++++++++++++------------------ src/comm/MAVLinkProtocol.h | 4 --- 5 files changed, 67 insertions(+), 60 deletions(-) diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index d5a66d367..4e0904869 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -503,31 +503,39 @@ void QGCApplication::criticalMessageBoxOnMainThread(const QString& title, const #endif } -#ifndef __mobile__ void QGCApplication::saveTelemetryLogOnMainThread(QString tempLogfile) { - // The vehicle is gone now and we are shutting down so we need to use a message box for errors to hold shutdown and show the error - if (_checkTelemetrySavePath(true /* useMessageBox */)) { - - QString saveDirPath = _toolbox->settingsManager()->appSettings()->telemetrySavePath(); - QDir saveDir(saveDirPath); - - QString nameFormat("%1%2.tlog"); - QString dtFormat("yyyy-MM-dd hh-mm-ss"); - - int tryIndex = 1; - QString saveFileName = nameFormat.arg(QDateTime::currentDateTime().toString(dtFormat)).arg(""); - while (saveDir.exists(saveFileName)) { - saveFileName = nameFormat.arg(QDateTime::currentDateTime().toString(dtFormat)).arg(QStringLiteral(".%1").arg(tryIndex++)); - } - QString saveFilePath = saveDir.absoluteFilePath(saveFileName); + // Are we supposed to log? + if(toolbox()->settingsManager()->appSettings()->telemetrySave()->rawValue().toBool()) { + // The vehicle is gone now and we are shutting down so we need to use a message box for errors to hold shutdown and show the error + if (_checkTelemetrySavePath(true /* useMessageBox */)) { + + QString saveDirPath = _toolbox->settingsManager()->appSettings()->telemetrySavePath(); + QDir saveDir(saveDirPath); + + QString nameFormat("%1%2.%3"); + QString dtFormat("yyyy-MM-dd hh-mm-ss"); + + int tryIndex = 1; + QString saveFileName = nameFormat.arg( + QDateTime::currentDateTime().toString(dtFormat)).arg("").arg(toolbox()->settingsManager()->appSettings()->telemetryFileExtension); + while (saveDir.exists(saveFileName)) { + saveFileName = nameFormat.arg( + QDateTime::currentDateTime().toString(dtFormat)).arg(QStringLiteral(".%1").arg(tryIndex++)).arg(toolbox()->settingsManager()->appSettings()->telemetryFileExtension); + } + QString saveFilePath = saveDir.absoluteFilePath(saveFileName); - QFile tempFile(tempLogfile); - if (!tempFile.copy(saveFilePath)) { - QGCMessageBox::warning(tr("Telemetry save error"), tr("Unable to save telemetry log. Error copying telemetry to '%1': '%2'.").arg(saveFilePath).arg(tempFile.errorString())); + QFile tempFile(tempLogfile); + if (!tempFile.copy(saveFilePath)) { + QString error = tr("Unable to save telemetry log. Error copying telemetry to '%1': '%2'.").arg(saveFilePath).arg(tempFile.errorString()); +#ifndef __mobile__ + QGCMessageBox::warning(tr("Telemetry Save Error"), error); +#else + showMessage(error); +#endif + } } } - QFile::remove(tempLogfile); } @@ -544,28 +552,36 @@ bool QGCApplication::_checkTelemetrySavePath(bool useMessageBox) QString saveDirPath = _toolbox->settingsManager()->appSettings()->telemetrySavePath(); if (saveDirPath.isEmpty()) { QString error = tr("Unable to save telemetry log. Application save directory is not set."); +#ifndef __mobile__ if (useMessageBox) { QGCMessageBox::warning(errorTitle, error); } else { +#endif + Q_UNUSED(useMessageBox); showMessage(error); +#ifndef __mobile__ } +#endif return false; } QDir saveDir(saveDirPath); if (!saveDir.exists()) { QString error = tr("Unable to save telemetry log. Telemetry save directory \"%1\" does not exist.").arg(saveDirPath); +#ifndef __mobile__ if (useMessageBox) { QGCMessageBox::warning(errorTitle, error); } else { +#endif showMessage(error); +#ifndef __mobile__ } +#endif return false; } return true; } -#endif void QGCApplication::_loadCurrentStyleSheet(void) { diff --git a/src/QGCApplication.h b/src/QGCApplication.h index 5aea0aa46..4d264d0f7 100644 --- a/src/QGCApplication.h +++ b/src/QGCApplication.h @@ -106,13 +106,11 @@ public slots: void qmlAttemptWindowClose(void); -#ifndef __mobile__ /// Save the specified telemetry Log void saveTelemetryLogOnMainThread(QString tempLogfile); /// Check that the telemetry save path is set correctly void checkTelemetrySavePathOnMainThread(void); -#endif signals: /// This is connected to MAVLinkProtocol::checkForLostLogFiles. We signal this to ourselves to call the slot diff --git a/src/api/QGCCorePlugin.cc b/src/api/QGCCorePlugin.cc index 909fa3f9b..dfb444d05 100644 --- a/src/api/QGCCorePlugin.cc +++ b/src/api/QGCCorePlugin.cc @@ -155,8 +155,8 @@ bool QGCCorePlugin::overrideSettingsGroupVisibility(QString name) bool QGCCorePlugin::adjustSettingMetaData(FactMetaData& metaData) { + //-- Default Palette if (metaData.name() == AppSettings::indoorPaletteName) { - // Set up correct default for palette setting QVariant outdoorPalette; #if defined (__mobile__) outdoorPalette = 0; @@ -164,9 +164,18 @@ bool QGCCorePlugin::adjustSettingMetaData(FactMetaData& metaData) outdoorPalette = 1; #endif metaData.setRawDefaultValue(outdoorPalette); + return true; + //-- Auto Save Telemetry Logs + } else if (metaData.name() == AppSettings::telemetrySaveName) { +#if defined (__mobile__) + metaData.setRawDefaultValue(false); + return false; +#else + metaData.setRawDefaultValue(true); + return true; +#endif } - - return true; // Show setting in ui + return true; // Show setting in ui } void QGCCorePlugin::setShowTouchAreas(bool show) diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index 77b240b62..d02ab8ca7 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -41,10 +41,8 @@ Q_DECLARE_METATYPE(mavlink_message_t) QGC_LOGGING_CATEGORY(MAVLinkProtocolLog, "MAVLinkProtocolLog") -#ifndef __mobile__ const char* MAVLinkProtocol::_tempLogFileTemplate = "FlightDataXXXXXX"; ///< Template for temporary log file const char* MAVLinkProtocol::_logFileExtension = "mavlink"; ///< Extension for log files -#endif /** * The default constructor will create a new MAVLink object sending heartbeats at @@ -55,12 +53,10 @@ MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app, QGCToolbox* toolbox) , m_enable_version_check(true) , versionMismatchIgnore(false) , systemId(255) -#ifndef __mobile__ , _logSuspendError(false) , _logSuspendReplay(false) , _vehicleWasArmed(false) , _tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension)) -#endif , _linkMgr(NULL) , _multiVehicleManager(NULL) { @@ -74,10 +70,7 @@ MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app, QGCToolbox* toolbox) MAVLinkProtocol::~MAVLinkProtocol() { storeSettings(); - -#ifndef __mobile__ _closeLogFile(); -#endif } void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox) @@ -104,10 +97,8 @@ void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox) } connect(this, &MAVLinkProtocol::protocolStatusMessage, _app, &QGCApplication::criticalMessageBoxOnMainThread); -#ifndef __mobile__ connect(this, &MAVLinkProtocol::saveTelemetryLog, _app, &QGCApplication::saveTelemetryLogOnMainThread); connect(this, &MAVLinkProtocol::checkTelemetrySavePath, _app, &QGCApplication::checkTelemetrySavePathOnMainThread); -#endif connect(_multiVehicleManager->vehicles(), &QmlObjectListModel::countChanged, this, &MAVLinkProtocol::_vehicleCountChanged); @@ -208,9 +199,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) link->setDecodedFirstMavlinkPacket(true); } -#ifndef __mobile__ // Log data - if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) { uint8_t buf[MAVLINK_MAX_PACKET_LEN+sizeof(quint64)]; @@ -245,14 +234,10 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) } } } -#endif if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) { -#ifndef __mobile__ // Start loggin on first heartbeat _startLogging(); -#endif - mavlink_heartbeat_t heartbeat; mavlink_msg_heartbeat_decode(&message, &heartbeat); emit vehicleHeartbeatInfo(link, message.sysid, message.compid, heartbeat.mavlink_version, heartbeat.autopilot, heartbeat.type); @@ -342,17 +327,12 @@ void MAVLinkProtocol::enableVersionCheck(bool enabled) void MAVLinkProtocol::_vehicleCountChanged(int count) { -#ifndef __mobile__ if (count == 0) { // Last vehicle is gone, close out logging _stopLogging(); } -#else - Q_UNUSED(count); -#endif } -#ifndef __mobile__ /// @brief Closes the log file if it is open bool MAVLinkProtocol::_closeLogFile(void) { @@ -367,16 +347,23 @@ bool MAVLinkProtocol::_closeLogFile(void) return true; } } - return false; } void MAVLinkProtocol::_startLogging(void) { + //-- Are we supposed to write logs? if (qgcApp()->runningUnitTests()) { return; } - +#ifdef __mobile__ + //-- Mobile build don't write to /tmp unless told to do so + if (!_app->toolbox()->settingsManager()->appSettings()->telemetrySave()->rawValue().toBool()) { + return; + } +#endif + //-- Log is always written to a temp file. If later the user decides they want + // it, it's all there for them. if (!_tempLogFile.isOpen()) { if (!_logSuspendReplay) { if (!_tempLogFile.open()) { @@ -397,12 +384,14 @@ void MAVLinkProtocol::_startLogging(void) void MAVLinkProtocol::_stopLogging(void) { - if (_closeLogFile()) { - SettingsManager* settingsManager = _app->toolbox()->settingsManager(); - if ((_vehicleWasArmed || settingsManager->appSettings()->telemetrySaveNotArmed()->rawValue().toBool()) && settingsManager->appSettings()->telemetrySave()->rawValue().toBool()) { - emit saveTelemetryLog(_tempLogFile.fileName()); - } else { - QFile::remove(_tempLogFile.fileName()); + if (_tempLogFile.isOpen()) { + if (_closeLogFile()) { + if ((_vehicleWasArmed || _app->toolbox()->settingsManager()->appSettings()->telemetrySaveNotArmed()->rawValue().toBool()) && + _app->toolbox()->settingsManager()->appSettings()->telemetrySave()->rawValue().toBool()) { + emit saveTelemetryLog(_tempLogFile.fileName()); + } else { + QFile::remove(_tempLogFile.fileName()); + } } } _vehicleWasArmed = false; @@ -426,7 +415,6 @@ void MAVLinkProtocol::checkForLostLogFiles(void) QFile::remove(fileInfo.filePath()); continue; } - emit saveTelemetryLog(fileInfo.filePath()); } } @@ -447,4 +435,4 @@ void MAVLinkProtocol::deleteTempLogFiles(void) QFile::remove(fileInfo.filePath()); } } -#endif + diff --git a/src/comm/MAVLinkProtocol.h b/src/comm/MAVLinkProtocol.h index 03026529d..9d3ad1364 100644 --- a/src/comm/MAVLinkProtocol.h +++ b/src/comm/MAVLinkProtocol.h @@ -108,13 +108,11 @@ public slots: /** @brief Store protocol settings */ void storeSettings(); -#ifndef __mobile__ /// @brief Deletes any log files which are in the temp directory static void deleteTempLogFiles(void); /// Checks for lost log files void checkForLostLogFiles(void); -#endif protected: bool m_enable_version_check; ///< Enable checking of version match of MAV and QGC @@ -168,7 +166,6 @@ private slots: void _vehicleCountChanged(int count); private: -#ifndef __mobile__ bool _closeLogFile(void); void _startLogging(void); void _stopLogging(void); @@ -180,7 +177,6 @@ private: QGCTemporaryFile _tempLogFile; ///< File to log to static const char* _tempLogFileTemplate; ///< Template for temporary log file static const char* _logFileExtension; ///< Extension for log files -#endif LinkManager* _linkMgr; MultiVehicleManager* _multiVehicleManager; -- 2.22.0