diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index ff3681a652c14f26d9b72d3340ffed633c3b0947..42c3552ce5a3c87bc8642781f03f1e7578704a2c 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -108,9 +108,7 @@ void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox) connect(this, &MAVLinkProtocol::protocolStatusMessage, _app, &QGCApplication::criticalMessageBoxOnMainThread); connect(this, &MAVLinkProtocol::saveTempFlightDataLog, _app, &QGCApplication::saveTempFlightDataLogOnMainThread); -#ifndef __mobile__ connect(_multiVehicleManager->vehicles(), &QmlObjectListModel::countChanged, this, &MAVLinkProtocol::_vehicleCountChanged); -#endif emit versionCheckChanged(m_enable_version_check); } @@ -631,6 +629,18 @@ int MAVLinkProtocol::getHeartbeatRate() return _heartbeatRate; } +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) @@ -726,12 +736,4 @@ void MAVLinkProtocol::deleteTempLogFiles(void) QFile::remove(fileInfo.filePath()); } } - -void MAVLinkProtocol::_vehicleCountChanged(int count) -{ - if (count == 0) { - // Last vehicle is gone, close out logging - _stopLogging(); - } -} #endif