diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 4230ee0..84cdab1 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -448,9 +448,11 @@ bool QGCApplication::_initForNormalAppBoot(void) splashScreen->finish(mainWindow); mainWindow->splashScreenFinished(); +#ifndef __mobile__ // Now that main window is up check for lost log files connect(this, &QGCApplication::checkForLostLogFiles, MAVLinkProtocol::instance(), &MAVLinkProtocol::checkForLostLogFiles); emit checkForLostLogFiles(); +#endif // Load known link configurations LinkManager::instance()->loadLinkConfigurationList(); diff --git a/src/comm/LogReplayLink.cc b/src/comm/LogReplayLink.cc index 05836d2..ca0d1fb 100644 --- a/src/comm/LogReplayLink.cc +++ b/src/comm/LogReplayLink.cc @@ -367,7 +367,9 @@ void LogReplayLink::_play(void) { // FIXME: With move to link I don't think this is needed any more? Except for the replay widget handling multi-uas? LinkManager::instance()->setConnectionsSuspended(tr("Connect not allowed during Flight Data replay.")); +#ifndef __mobile__ MAVLinkProtocol::instance()->suspendLogForReplay(true); +#endif // Make sure we aren't at the end of the file, if we are, reset to the beginning and play from there. if (_logFile.atEnd()) { @@ -397,7 +399,9 @@ void LogReplayLink::_play(void) void LogReplayLink::_pause(void) { LinkManager::instance()->setConnectionsAllowed(); +#ifndef __mobile__ MAVLinkProtocol::instance()->suspendLogForReplay(false); +#endif _readTickTimer.stop(); diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index e122d57..30543e2 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -33,8 +33,10 @@ Q_DECLARE_METATYPE(mavlink_message_t) IMPLEMENT_QGC_SINGLETON(MAVLinkProtocol, MAVLinkProtocol) 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 @@ -52,10 +54,12 @@ MAVLinkProtocol::MAVLinkProtocol(QObject* parent) : m_actionRetransmissionTimeout(100), versionMismatchIgnore(false), systemId(QGC::defaultSystemId), +#ifndef __mobile__ _logSuspendError(false), _logSuspendReplay(false), _logWasArmed(false), _tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension)), +#endif _linkMgr(LinkManager::instance()), _heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE), _heartbeatsEnabled(true) @@ -91,7 +95,9 @@ MAVLinkProtocol::~MAVLinkProtocol() { storeSettings(); +#ifndef __mobile__ _closeLogFile(); +#endif } void MAVLinkProtocol::loadSettings() @@ -181,10 +187,12 @@ void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected) // Use the same shared pointer as LinkManager _connectedLinks.append(LinkManager::instance()->sharedPointerForLink(link)); +#ifndef __mobile__ if (_connectedLinks.count() == 1) { // This is the first link, we need to start logging _startLogging(); } +#endif // Send command to start MAVLink // XXX hacky but safe @@ -206,10 +214,12 @@ void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected) Q_UNUSED(found); Q_ASSERT(found); +#ifndef __mobile__ if (_connectedLinks.count() == 0) { // Last link is gone, close out logging _stopLogging(); } +#endif } } @@ -303,6 +313,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) rstatus.txbuf, rstatus.noise, rstatus.remnoise); } +#ifndef __mobile__ // Log data if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) { @@ -339,6 +350,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) } } } +#endif if (message.msgid == MAVLINK_MSG_ID_HEARTBEAT) { // Notify the vehicle manager of the heartbeat. This will create/update vehicles as needed. @@ -613,6 +625,7 @@ int MAVLinkProtocol::getHeartbeatRate() return _heartbeatRate; } +#ifndef __mobile__ /// @brief Closes the log file if it is open bool MAVLinkProtocol::_closeLogFile(void) { @@ -707,3 +720,4 @@ void MAVLinkProtocol::deleteTempLogFiles(void) QFile::remove(fileInfo.filePath()); } } +#endif diff --git a/src/comm/MAVLinkProtocol.h b/src/comm/MAVLinkProtocol.h index 08387ff..2549e0a 100644 --- a/src/comm/MAVLinkProtocol.h +++ b/src/comm/MAVLinkProtocol.h @@ -203,11 +203,13 @@ 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_multiplexingEnabled; ///< Enable/disable packet multiplexing @@ -281,22 +283,25 @@ private: ~MAVLinkProtocol(); void _linkStatusChanged(LinkInterface* link, bool connected); + +#ifndef __mobile__ bool _closeLogFile(void); void _startLogging(void); void _stopLogging(void); - - /// List of all links connected to protocol. We keep SharedLinkInterface objects - /// which are QSharedPointer's in order to maintain reference counts across threads. - /// This way Link deletion works correctly. - QList _connectedLinks; - + bool _logSuspendError; ///< true: Logging suspended due to error bool _logSuspendReplay; ///< true: Logging suspended due to replay bool _logWasArmed; ///< true: vehicle was armed during logging - + QGCTemporaryFile _tempLogFile; ///< File to log to static const char* _tempLogFileTemplate; ///< Template for temporary log file static const char* _logFileExtension; ///< Extension for log files +#endif + + /// List of all links connected to protocol. We keep SharedLinkInterface objects + /// which are QSharedPointer's in order to maintain reference counts across threads. + /// This way Link deletion works correctly. + QList _connectedLinks; LinkManager* _linkMgr;