|
|
@ -108,6 +108,10 @@ void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox) |
|
|
|
connect(this, &MAVLinkProtocol::protocolStatusMessage, _app, &QGCApplication::criticalMessageBoxOnMainThread); |
|
|
|
connect(this, &MAVLinkProtocol::protocolStatusMessage, _app, &QGCApplication::criticalMessageBoxOnMainThread); |
|
|
|
connect(this, &MAVLinkProtocol::saveTempFlightDataLog, _app, &QGCApplication::saveTempFlightDataLogOnMainThread); |
|
|
|
connect(this, &MAVLinkProtocol::saveTempFlightDataLog, _app, &QGCApplication::saveTempFlightDataLogOnMainThread); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
#ifndef __mobile__ |
|
|
|
|
|
|
|
connect(_multiVehicleManager->vehicles(), &QmlObjectListModel::countChanged, this, &MAVLinkProtocol::_vehicleCountChanged); |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
emit versionCheckChanged(m_enable_version_check); |
|
|
|
emit versionCheckChanged(m_enable_version_check); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -217,13 +221,6 @@ void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected) |
|
|
|
} |
|
|
|
} |
|
|
|
Q_UNUSED(found); |
|
|
|
Q_UNUSED(found); |
|
|
|
Q_ASSERT(found); |
|
|
|
Q_ASSERT(found); |
|
|
|
|
|
|
|
|
|
|
|
#ifndef __mobile__ |
|
|
|
|
|
|
|
if (_connectedLinks.count() == 0) { |
|
|
|
|
|
|
|
// Last link is gone, close out logging
|
|
|
|
|
|
|
|
_stopLogging(); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
#endif |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -729,4 +726,12 @@ void MAVLinkProtocol::deleteTempLogFiles(void) |
|
|
|
QFile::remove(fileInfo.filePath()); |
|
|
|
QFile::remove(fileInfo.filePath()); |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void MAVLinkProtocol::_vehicleCountChanged(int count) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
if (count == 0) { |
|
|
|
|
|
|
|
// Last vehicle is gone, close out logging
|
|
|
|
|
|
|
|
_stopLogging(); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
#endif |
|
|
|
#endif |
|
|
|