diff --git a/src/AnalyzeView/LogDownloadController.cc b/src/AnalyzeView/LogDownloadController.cc index 1070cffd449..59d6e1f8585 100644 --- a/src/AnalyzeView/LogDownloadController.cc +++ b/src/AnalyzeView/LogDownloadController.cc @@ -394,8 +394,8 @@ LogDownloadController::_requestLogData(uint16_t id, uint32_t offset, uint32_t co qCDebug(LogDownloadControllerLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count << "retryCount" << retryCount << ")"; mavlink_message_t msg; mavlink_msg_log_request_data_pack_chan( - qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), + MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, _vehicle->id(), _vehicle->defaultComponentId(), @@ -425,8 +425,8 @@ LogDownloadController::_requestLogList(uint32_t start, uint32_t end) if (sharedLink) { mavlink_message_t msg; mavlink_msg_log_request_list_pack_chan( - qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), + MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, _vehicle->id(), @@ -596,8 +596,8 @@ LogDownloadController::eraseAll(void) if (sharedLink) { mavlink_message_t msg; mavlink_msg_log_erase_pack_chan( - qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), + MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->defaultComponentId()); diff --git a/src/AnalyzeView/MAVLinkConsoleController.cc b/src/AnalyzeView/MAVLinkConsoleController.cc index 44e6e15372a..7c1f8772671 100644 --- a/src/AnalyzeView/MAVLinkConsoleController.cc +++ b/src/AnalyzeView/MAVLinkConsoleController.cc @@ -159,12 +159,10 @@ void MAVLinkConsoleController::_sendSerialData(const QByteArray &data, bool clos const uint8_t flags = close ? 0 : SERIAL_CONTROL_FLAG_EXCLUSIVE | SERIAL_CONTROL_FLAG_RESPOND | SERIAL_CONTROL_FLAG_MULTI; - MAVLinkProtocol *const protocol = qgcApp()->toolbox()->mavlinkProtocol(); - mavlink_message_t msg; (void) mavlink_msg_serial_control_pack_chan( - protocol->getSystemId(), - protocol->getComponentId(), + MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, SERIAL_CONTROL_DEV_SHELL, diff --git a/src/AnalyzeView/MAVLinkInspectorController.cc b/src/AnalyzeView/MAVLinkInspectorController.cc index 290da65c7a6..9fb2e66f6d2 100644 --- a/src/AnalyzeView/MAVLinkInspectorController.cc +++ b/src/AnalyzeView/MAVLinkInspectorController.cc @@ -28,8 +28,7 @@ MAVLinkInspectorController::MAVLinkInspectorController() connect(multiVehicleManager, &MultiVehicleManager::vehicleAdded, this, &MAVLinkInspectorController::_vehicleAdded); connect(multiVehicleManager, &MultiVehicleManager::vehicleRemoved, this, &MAVLinkInspectorController::_vehicleRemoved); connect(multiVehicleManager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkInspectorController::_setActiveVehicle); - MAVLinkProtocol* mavlinkProtocol = qgcApp()->toolbox()->mavlinkProtocol(); - connect(mavlinkProtocol, &MAVLinkProtocol::messageReceived, this, &MAVLinkInspectorController::_receiveMessage); + connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, &MAVLinkInspectorController::_receiveMessage); connect(&_updateFrequencyTimer, &QTimer::timeout, this, &MAVLinkInspectorController::_refreshFrequency); _updateFrequencyTimer.start(1000); _timeScaleSt.append(new TimeScale_st(this, tr("5 Sec"), 5 * 1000)); diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc index a59852f2cb0..0124e369ff7 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc @@ -103,7 +103,7 @@ void APMSensorsComponentController::_startLogCalibration(void) } _cancelButton->setEnabled(_calTypeInProgress == QGCMAVLink::CalibrationMag); - connect(qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::messageReceived, this, &APMSensorsComponentController::_mavlinkMessageReceived); + connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, &APMSensorsComponentController::_mavlinkMessageReceived); } void APMSensorsComponentController::_startVisualCalibration(void) @@ -116,7 +116,7 @@ void APMSensorsComponentController::_startVisualCalibration(void) _progressBar->setProperty("value", 0); - connect(qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::messageReceived, this, &APMSensorsComponentController::_mavlinkMessageReceived); + connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, &APMSensorsComponentController::_mavlinkMessageReceived); } void APMSensorsComponentController::_resetInternalState(void) @@ -147,7 +147,7 @@ void APMSensorsComponentController::_resetInternalState(void) void APMSensorsComponentController::_stopCalibration(APMSensorsComponentController::StopCalibrationCode code) { - disconnect(qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::messageReceived, this, &APMSensorsComponentController::_mavlinkMessageReceived); + disconnect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, &APMSensorsComponentController::_mavlinkMessageReceived); _vehicle->vehicleLinkManager()->setCommunicationLostEnabled(true); disconnect(_vehicle, &Vehicle::textMessageReceived, this, &APMSensorsComponentController::_handleUASTextMessage); @@ -462,8 +462,8 @@ void APMSensorsComponentController::nextClicked(void) if (sharedLink) { mavlink_message_t msg; - mavlink_msg_command_ack_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), + mavlink_msg_command_ack_pack_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, 0, // command diff --git a/src/Camera/QGCCameraIO.cc b/src/Camera/QGCCameraIO.cc index 52da8bd2b43..f3e40159c6a 100644 --- a/src/Camera/QGCCameraIO.cc +++ b/src/Camera/QGCCameraIO.cc @@ -10,8 +10,6 @@ #include "MavlinkCameraControl.h" #include "QGCCameraIO.h" #include "QGCLoggingCategory.h" -#include "QGCApplication.h" -#include "QGCToolbox.h" #include "LinkInterface.h" #include "MAVLinkProtocol.h" #include "Vehicle.h" @@ -47,7 +45,6 @@ QGCCameraParamIO::QGCCameraParamIO(MavlinkCameraControl *control, Fact* fact, Ve connect(&_paramWriteTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramWriteTimeout); connect(_fact, &Fact::rawValueChanged, this, &QGCCameraParamIO::_factChanged); connect(_fact, &Fact::_containerRawValueChanged, this, &QGCCameraParamIO::_containerRawValueChanged); - _pMavlink = qgcApp()->toolbox()->mavlinkProtocol(); //-- TODO: Even though we don't use anything larger than 32-bit, this should // probably be updated. switch (_fact->type()) { @@ -196,8 +193,8 @@ QGCCameraParamIO::_sendParameter() p.target_component = static_cast(_control->compID()); strncpy(p.param_id, _fact->name().toStdString().c_str(), MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_ID_LEN); mavlink_msg_param_ext_set_encode_chan( - static_cast(_pMavlink->getSystemId()), - static_cast(_pMavlink->getComponentId()), + static_cast(MAVLinkProtocol::instance()->getSystemId()), + static_cast(MAVLinkProtocol::instance()->getComponentId()), sharedLink->mavlinkChannel(), &msg, &p); @@ -369,8 +366,8 @@ QGCCameraParamIO::paramRequest(bool reset) strncpy(param_id, _fact->name().toStdString().c_str(), MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN); mavlink_message_t msg; mavlink_msg_param_ext_request_read_pack_chan( - static_cast(_pMavlink->getSystemId()), - static_cast(_pMavlink->getComponentId()), + static_cast(MAVLinkProtocol::instance()->getSystemId()), + static_cast(MAVLinkProtocol::instance()->getComponentId()), sharedLink->mavlinkChannel(), &msg, static_cast(_vehicle->id()), diff --git a/src/Camera/QGCCameraIO.h b/src/Camera/QGCCameraIO.h index 5d2ce7ef97f..bd61fb43092 100644 --- a/src/Camera/QGCCameraIO.h +++ b/src/Camera/QGCCameraIO.h @@ -15,7 +15,6 @@ class MavlinkCameraControl; class Fact; class Vehicle; -class MAVLinkProtocol; Q_DECLARE_LOGGING_CATEGORY(CameraIOLog) Q_DECLARE_LOGGING_CATEGORY(CameraIOLogVerbose) @@ -77,7 +76,6 @@ private slots: bool _done; bool _updateOnSet; MAV_PARAM_EXT_TYPE _mavParamType; - MAVLinkProtocol* _pMavlink; bool _forceUIUpdate; }; diff --git a/src/Camera/VehicleCameraControl.cc b/src/Camera/VehicleCameraControl.cc index 9b617019467..328589e7938 100644 --- a/src/Camera/VehicleCameraControl.cc +++ b/src/Camera/VehicleCameraControl.cc @@ -1153,11 +1153,10 @@ VehicleCameraControl::_requestAllParameters() } SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); if (sharedLink) { - MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); mavlink_message_t msg; mavlink_msg_param_ext_request_list_pack_chan( - static_cast(mavlink->getSystemId()), - static_cast(mavlink->getComponentId()), + static_cast(MAVLinkProtocol::instance()->getSystemId()), + static_cast(MAVLinkProtocol::instance()->getComponentId()), sharedLink->mavlinkChannel(), &msg, static_cast(_vehicle->id()), diff --git a/src/Comms/AirLink/AirLinkLink.cc b/src/Comms/AirLink/AirLinkLink.cc index 427fe731bf4..6a5ba33e054 100644 --- a/src/Comms/AirLink/AirLinkLink.cc +++ b/src/Comms/AirLink/AirLinkLink.cc @@ -61,7 +61,7 @@ void AirLinkLink::disconnect() bool AirLinkLink::_connect() { std::shared_ptr conn = std::make_shared(); - *conn = connect(qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::messageReceived, this, [this, conn] (const LinkInterface* linkSrc, const mavlink_message_t &message) { + *conn = connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, [this, conn] (const LinkInterface* linkSrc, const mavlink_message_t &message) { if (this != linkSrc || message.msgid != MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE) { return; } diff --git a/src/Comms/LinkManager.cc b/src/Comms/LinkManager.cc index 59ef96a542b..bbcfe8f593a 100644 --- a/src/Comms/LinkManager.cc +++ b/src/Comms/LinkManager.cc @@ -88,7 +88,6 @@ void LinkManager::setToolbox(QGCToolbox *toolbox) QGCTool::setToolbox(toolbox); _autoConnectSettings = toolbox->settingsManager()->autoConnectSettings(); - _mavlinkProtocol = _toolbox->mavlinkProtocol(); if (!qgcApp()->runningUnitTests()) { (void) connect(_portListTimer, &QTimer::timeout, this, &LinkManager::_updateAutoConnectLinks); @@ -162,12 +161,12 @@ bool LinkManager::createConnectedLink(SharedLinkConfigurationPtr &config) config->setLink(link); (void) connect(link.get(), &LinkInterface::communicationError, _app, &QGCApplication::criticalMessageBoxOnMainThread); - (void) connect(link.get(), &LinkInterface::bytesReceived, _mavlinkProtocol, &MAVLinkProtocol::receiveBytes); - (void) connect(link.get(), &LinkInterface::bytesSent, _mavlinkProtocol, &MAVLinkProtocol::logSentBytes); + (void) connect(link.get(), &LinkInterface::bytesReceived, MAVLinkProtocol::instance(), &MAVLinkProtocol::receiveBytes); + (void) connect(link.get(), &LinkInterface::bytesSent, MAVLinkProtocol::instance(), &MAVLinkProtocol::logSentBytes); (void) connect(link.get(), &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected); - _mavlinkProtocol->resetMetadataForLink(link.get()); - _mavlinkProtocol->setVersion(_mavlinkProtocol->getCurrentVersion()); + MAVLinkProtocol::instance()->resetMetadataForLink(link.get()); + MAVLinkProtocol::instance()->setVersion(MAVLinkProtocol::instance()->getCurrentVersion()); if (!link->_connect()) { link->_freeMavlinkChannel(); @@ -220,8 +219,8 @@ void LinkManager::_linkDisconnected() } (void) disconnect(link, &LinkInterface::communicationError, _app, &QGCApplication::criticalMessageBoxOnMainThread); - (void) disconnect(link, &LinkInterface::bytesReceived, _mavlinkProtocol, &MAVLinkProtocol::receiveBytes); - (void) disconnect(link, &LinkInterface::bytesSent, _mavlinkProtocol, &MAVLinkProtocol::logSentBytes); + (void) disconnect(link, &LinkInterface::bytesReceived, MAVLinkProtocol::instance(), &MAVLinkProtocol::receiveBytes); + (void) disconnect(link, &LinkInterface::bytesSent, MAVLinkProtocol::instance(), &MAVLinkProtocol::logSentBytes); (void) disconnect(link, &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected); link->_freeMavlinkChannel(); diff --git a/src/Comms/LinkManager.h b/src/Comms/LinkManager.h index 59359d7a69d..6a94b63cf7a 100644 --- a/src/Comms/LinkManager.h +++ b/src/Comms/LinkManager.h @@ -149,7 +149,6 @@ private slots: QString _connectionsSuspendedReason; ///< User visible reason for suspension AutoConnectSettings *_autoConnectSettings = nullptr; - MAVLinkProtocol *_mavlinkProtocol = nullptr; QTimer *_portListTimer = nullptr; QmlObjectListModel *_qmlConfigurations = nullptr; diff --git a/src/Comms/LogReplayLink.cc b/src/Comms/LogReplayLink.cc index 53a86112d1d..ffb8155d9ee 100644 --- a/src/Comms/LogReplayLink.cc +++ b/src/Comms/LogReplayLink.cc @@ -360,7 +360,7 @@ void LogReplayLink::_play(void) { qgcApp()->toolbox()->linkManager()->setConnectionsSuspended(tr("Connect not allowed during Flight Data replay.")); #ifndef __mobile__ - qgcApp()->toolbox()->mavlinkProtocol()->suspendLogForReplay(true); + 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. @@ -379,7 +379,7 @@ void LogReplayLink::_pause(void) { qgcApp()->toolbox()->linkManager()->setConnectionsAllowed(); #ifndef __mobile__ - qgcApp()->toolbox()->mavlinkProtocol()->suspendLogForReplay(false); + MAVLinkProtocol::instance()->suspendLogForReplay(false); #endif _readTickTimer.stop(); diff --git a/src/Comms/MAVLinkProtocol.cc b/src/Comms/MAVLinkProtocol.cc index 4653333e1cd..8ca5efd6396 100644 --- a/src/Comms/MAVLinkProtocol.cc +++ b/src/Comms/MAVLinkProtocol.cc @@ -9,529 +9,472 @@ #include "MAVLinkProtocol.h" #include "LinkManager.h" -#include "QGCApplication.h" #include "MultiVehicleManager.h" -#include "SettingsManager.h" +#include "QGCApplication.h" #include "QGCLoggingCategory.h" +#include "QGCTemporaryFile.h" +#include "QGCToolbox.h" +#include "SettingsManager.h" -#include -#include -#include #include #include +#include +#include +#include -#include - -Q_DECLARE_METATYPE(mavlink_message_t) +QGC_LOGGING_CATEGORY(MAVLinkProtocolLog, "qgc.comms.mavlinkprotocol") -QGC_LOGGING_CATEGORY(MAVLinkProtocolLog, "MAVLinkProtocolLog") +Q_APPLICATION_STATIC(MAVLinkProtocol, _mavlinkProtocol); -static QObject* mavlinkSingletonFactory(QQmlEngine*, QJSEngine*) +MAVLinkProtocol::MAVLinkProtocol(QObject *parent) + : QObject(parent) + , _tempLogFile(new QGCTemporaryFile(QStringLiteral("%2.%3").arg(_tempLogFileTemplate, _logFileExtension), this)) { - return new QGCMAVLink(); -} + // qCDebug(MAVLinkProtocolLog) << Q_FUNC_INFO << this; -/** - * The default constructor will create a new MAVLink object sending heartbeats at - * the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links. - */ -MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app, QGCToolbox* toolbox) - : QGCTool(app, toolbox) - , _enable_version_check(true) - , _message({}) - , _status({}) - , versionMismatchIgnore(false) - , systemId(255) - , _current_version(100) - , _radio_version_mismatch_count(0) - , _logSuspendError(false) - , _logSuspendReplay(false) - , _vehicleWasArmed(false) - , _tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension)) - , _linkMgr(nullptr) - , _multiVehicleManager(nullptr) -{ - memset(totalReceiveCounter, 0, sizeof(totalReceiveCounter)); - memset(totalLossCounter, 0, sizeof(totalLossCounter)); - memset(runningLossPercent, 0, sizeof(runningLossPercent)); - memset(firstMessage, 1, sizeof(firstMessage)); - memset(&_status, 0, sizeof(_status)); - memset(&_message, 0, sizeof(_message)); + (void) memset(_firstMessage, 1, sizeof(_firstMessage)); + + (void) connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleRemoved, this, &MAVLinkProtocol::_vehicleCountChanged); + + _loadSettings(); } MAVLinkProtocol::~MAVLinkProtocol() { - storeSettings(); + _storeSettings(); _closeLogFile(); + + // qCDebug(MAVLinkProtocolLog) << Q_FUNC_INFO << this; } -void MAVLinkProtocol::setVersion(unsigned version) +MAVLinkProtocol *MAVLinkProtocol::instance() { - QList sharedLinks = _linkMgr->links(); - - for (int i = 0; i < sharedLinks.length(); i++) { - mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(sharedLinks[i].get()->mavlinkChannel()); - - // Set flags for version - if (version < 200) { - mavlinkStatus->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1; - } else { - mavlinkStatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1; - } - } - - _current_version = version; + return _mavlinkProtocol(); } -void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox) +void MAVLinkProtocol::setVersion(unsigned version) { - QGCTool::setToolbox(toolbox); - - _linkMgr = _toolbox->linkManager(); - _multiVehicleManager = _toolbox->multiVehicleManager(); - - qmlRegisterSingletonType("MAVLink", 1, 0, "MAVLink", mavlinkSingletonFactory); - qRegisterMetaType("mavlink_message_t"); - - loadSettings(); - - // All the *Counter variables are not initialized here, as they should be initialized - // on a per-link basis before those links are used. @see resetMetadataForLink(). - - connect(this, &MAVLinkProtocol::protocolStatusMessage, _app, &QGCApplication::criticalMessageBoxOnMainThread); - connect(this, &MAVLinkProtocol::saveTelemetryLog, _app, &QGCApplication::saveTelemetryLogOnMainThread); - connect(this, &MAVLinkProtocol::checkTelemetrySavePath, _app, &QGCApplication::checkTelemetrySavePathOnMainThread); - - connect(_multiVehicleManager, &MultiVehicleManager::vehicleAdded, this, &MAVLinkProtocol::_vehicleCountChanged); - connect(_multiVehicleManager, &MultiVehicleManager::vehicleRemoved, this, &MAVLinkProtocol::_vehicleCountChanged); + const QList sharedLinks = qgcApp()->toolbox()->linkManager()->links(); + for (const SharedLinkInterfacePtr &interface : sharedLinks) { + mavlink_set_proto_version(interface.get()->mavlinkChannel(), version / 100); + } - emit versionCheckChanged(_enable_version_check); + _currentVersion = version; } -void MAVLinkProtocol::loadSettings() +void MAVLinkProtocol::_loadSettings() { - // Load defaults from settings QSettings settings; settings.beginGroup("QGC_MAVLINK_PROTOCOL"); - enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", _enable_version_check).toBool()); - // Only set system id if it was valid - int temp = settings.value("GCS_SYSTEM_ID", systemId).toInt(); - if (temp > 0 && temp < 256) - { - systemId = temp; + enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", versionCheckEnabled()).toBool()); + + bool ok = false; + const uint temp = settings.value("GCS_SYSTEM_ID", getSystemId()).toUInt(&ok); + if (ok && (temp > 0) && (temp < 256)) { + setSystemId(temp); } + + settings.endGroup(); } -void MAVLinkProtocol::storeSettings() +void MAVLinkProtocol::_storeSettings() const { - // Store settings QSettings settings; settings.beginGroup("QGC_MAVLINK_PROTOCOL"); - settings.setValue("VERSION_CHECK_ENABLED", _enable_version_check); - settings.setValue("GCS_SYSTEM_ID", systemId); - // Parameter interface settings + + settings.setValue("VERSION_CHECK_ENABLED", versionCheckEnabled()); + settings.setValue("GCS_SYSTEM_ID", getSystemId()); + + settings.endGroup(); } void MAVLinkProtocol::resetMetadataForLink(LinkInterface *link) { - int channel = link->mavlinkChannel(); - totalReceiveCounter[channel] = 0; - totalLossCounter[channel] = 0; - runningLossPercent[channel] = 0.0f; - for(int i = 0; i < 256; i++) { - firstMessage[channel][i] = 1; + const uint8_t channel = link->mavlinkChannel(); + _totalReceiveCounter[channel] = 0; + _totalLossCounter[channel] = 0; + _runningLossPercent[channel] = 0.f; + for (int i = 0; i < 256; i++) { + _firstMessage[channel][i] = 1; } + link->setDecodedFirstMavlinkPacket(false); } -/** - * This method parses all outcoming bytes and log a MAVLink packet. - * @param link The interface to read from - * @see LinkInterface - **/ - -void MAVLinkProtocol::logSentBytes(LinkInterface* link, QByteArray b){ - - uint8_t bytes_time[sizeof(quint64)]; - +void MAVLinkProtocol::logSentBytes(const LinkInterface *link, const QByteArray &data) +{ Q_UNUSED(link); - if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) { - - quint64 time = static_cast(QDateTime::currentMSecsSinceEpoch() * 1000); - - qToBigEndian(time,bytes_time); - b.insert(0,QByteArray((const char*)bytes_time,sizeof(bytes_time))); + uint8_t bytes_time[sizeof(qint64)]; + if (_logSuspendError || _logSuspendReplay || !_tempLogFile->isOpen()) { + return; + } - int len = b.length(); + const qint64 time = QDateTime::currentMSecsSinceEpoch() * 1000; + qToBigEndian(time, bytes_time); - if(_tempLogFile.write(b) != len) - { - // If there's an error logging data, raise an alert and stop logging. - emit protocolStatusMessage(tr("MAVLink Protocol"), tr("MAVLink Logging failed. Could not write to file %1, logging disabled.").arg(_tempLogFile.fileName())); - _stopLogging(); - _logSuspendError = true; - } + const QByteArray logData = QByteArray::fromRawData(reinterpret_cast(bytes_time), sizeof(bytes_time)); + if (_tempLogFile->write(logData) == logData.length()) { + return; } + const QString message = QStringLiteral("MAVLink Logging failed. Could not write to file %1, logging disabled.").arg(_tempLogFile->fileName()); + qgcApp()->showAppMessage(message, getName()); + _stopLogging(); + _logSuspendError = true; } -/** - * This method parses all incoming bytes and constructs a MAVLink packet. - * It can handle multiple links in parallel, as each link has it's own buffer/ - * parsing state machine. - * @param link The interface to read from - * @see LinkInterface - **/ - -void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) +void MAVLinkProtocol::receiveBytes(LinkInterface *link, const QByteArray &data) { - // Since receiveBytes signals cross threads we can end up with signals in the queue - // that come through after the link is disconnected. For these we just drop the data - // since the link is closed. - SharedLinkInterfacePtr linkPtr = _linkMgr->sharedLinkInterfacePointerForLink(link); + const SharedLinkInterfacePtr linkPtr = qgcApp()->toolbox()->linkManager()->sharedLinkInterfacePointerForLink(link); if (!linkPtr) { - qCDebug(MAVLinkProtocolLog) << "receiveBytes: link gone!" << b.size() << " bytes arrived too late"; + qCDebug(MAVLinkProtocolLog) << "receiveBytes: link gone!" << data.size() << "bytes arrived too late"; return; } - uint8_t mavlinkChannel = link->mavlinkChannel(); - - for (int position = 0; position < b.size(); position++) { - if (mavlink_parse_char(mavlinkChannel, static_cast(b[position]), &_message, &_status)) { - // Got a valid message - if (!link->decodedFirstMavlinkPacket()) { - link->setDecodedFirstMavlinkPacket(true); - mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(mavlinkChannel); - if (!(mavlinkStatus->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) && (mavlinkStatus->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) { - qCDebug(MAVLinkProtocolLog) << "Switching outbound to mavlink 2.0 due to incoming mavlink 2.0 packet:" << mavlinkStatus << mavlinkChannel << mavlinkStatus->flags; - mavlinkStatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1; - // Set all links to v2 - setVersion(200); - } - } + for (const uint8_t &byte: data) { + const uint8_t mavlinkChannel = link->mavlinkChannel(); + mavlink_message_t message{}; + mavlink_status_t status{}; - //----------------------------------------------------------------- - // MAVLink Status - uint8_t lastSeq = lastIndex[_message.sysid][_message.compid]; - uint8_t expectedSeq = lastSeq + 1; - // Increase receive counter - totalReceiveCounter[mavlinkChannel]++; - // Determine what the next expected sequence number is, accounting for - // never having seen a message for this system/component pair. - if(firstMessage[_message.sysid][_message.compid]) { - firstMessage[_message.sysid][_message.compid] = 0; - lastSeq = _message.seq; - expectedSeq = _message.seq; - } - // And if we didn't encounter that sequence number, record the error - //int foo = 0; - if (_message.seq != expectedSeq) - { - //foo = 1; - int lostMessages = 0; - //-- Account for overflow during packet loss - if(_message.seq < expectedSeq) { - lostMessages = (_message.seq + 255) - expectedSeq; - } else { - lostMessages = _message.seq - expectedSeq; - } - // Log how many were lost - totalLossCounter[mavlinkChannel] += static_cast(lostMessages); - } + if (mavlink_parse_char(mavlinkChannel, byte, &message, &status) != MAVLINK_FRAMING_OK) { + continue; + } - // And update the last sequence number for this system/component pair - lastIndex[_message.sysid][_message.compid] = _message.seq;; - // Calculate new loss ratio - uint64_t totalSent = totalReceiveCounter[mavlinkChannel] + totalLossCounter[mavlinkChannel]; - float receiveLossPercent = static_cast(static_cast(totalLossCounter[mavlinkChannel]) / static_cast(totalSent)); - receiveLossPercent *= 100.0f; - receiveLossPercent = (receiveLossPercent * 0.5f) + (runningLossPercent[mavlinkChannel] * 0.5f); - runningLossPercent[mavlinkChannel] = receiveLossPercent; - - //qDebug() << foo << _message.seq << expectedSeq << lastSeq << totalLossCounter[mavlinkChannel] << totalReceiveCounter[mavlinkChannel] << totalSentCounter[mavlinkChannel] << "(" << _message.sysid << _message.compid << ")"; - - //----------------------------------------------------------------- - // MAVLink forwarding - bool forwardingEnabled = _app->toolbox()->settingsManager()->appSettings()->forwardMavlink()->rawValue().toBool(); - if (_message.msgid == MAVLINK_MSG_ID_SETUP_SIGNING) { - forwardingEnabled = false; - } - if (forwardingEnabled) { - SharedLinkInterfacePtr forwardingLink = _linkMgr->mavlinkForwardingLink(); - - if (forwardingLink) { - uint8_t buf[MAVLINK_MAX_PACKET_LEN]; - int len = mavlink_msg_to_send_buffer(buf, &_message); - forwardingLink->writeBytesThreadSafe((const char*)buf, len); - } - } + _updateVersion(link, mavlinkChannel); + _updateCounters(mavlinkChannel, message); + _forward(message); + _forwardSupport(message); + _logData(link, message); - // MAVLink forwarding support - bool forwardingSupportEnabled = _linkMgr->mavlinkSupportForwardingEnabled(); - if (_message.msgid == MAVLINK_MSG_ID_SETUP_SIGNING) { - forwardingSupportEnabled = false; - } - if (forwardingSupportEnabled) { - SharedLinkInterfacePtr forwardingSupportLink = _linkMgr->mavlinkForwardingSupportLink(); - - if (forwardingSupportLink) { - uint8_t buf[MAVLINK_MAX_PACKET_LEN]; - int len = mavlink_msg_to_send_buffer(buf, &_message); - forwardingSupportLink->writeBytesThreadSafe((const char*)buf, len); - } - } + if (!_updateStatus(link, linkPtr, mavlinkChannel, message)) { + break; + } + } +} - //----------------------------------------------------------------- - // Log data - if (!_logSuspendError && !_logSuspendReplay && _tempLogFile.isOpen()) { - uint8_t buf[MAVLINK_MAX_PACKET_LEN+sizeof(quint64)]; - - // Write the uint64 time in microseconds in big endian format before the message. - // This timestamp is saved in UTC time. We are only saving in ms precision because - // getting more than this isn't possible with Qt without a ton of extra code. - quint64 time = static_cast(QDateTime::currentMSecsSinceEpoch() * 1000); - qToBigEndian(time, buf); - - // Then write the message to the buffer - int len = mavlink_msg_to_send_buffer(buf + sizeof(quint64), &_message); - - // Determine how many bytes were written by adding the timestamp size to the message size - len += sizeof(quint64); - - // Now write this timestamp/message pair to the log. - QByteArray b(reinterpret_cast(buf), len); - if(_tempLogFile.write(b) != len) - { - // If there's an error logging data, raise an alert and stop logging. - emit protocolStatusMessage(tr("MAVLink Protocol"), tr("MAVLink Logging failed. Could not write to file %1, logging disabled.").arg(_tempLogFile.fileName())); - _stopLogging(); - _logSuspendError = true; - } - - // Check for the vehicle arming going by. This is used to trigger log save. - if (!_vehicleWasArmed && _message.msgid == MAVLINK_MSG_ID_HEARTBEAT) { - mavlink_heartbeat_t state; - mavlink_msg_heartbeat_decode(&_message, &state); - if (state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY) { - _vehicleWasArmed = true; - } - } - } +bool MAVLinkProtocol::_updateStatus(LinkInterface *link, const SharedLinkInterfacePtr linkPtr, uint8_t mavlinkChannel, const mavlink_message_t &message) +{ + if ((_totalReceiveCounter[mavlinkChannel] % 32) == 0) { + const uint64_t totalSent = _totalReceiveCounter[mavlinkChannel] + _totalLossCounter[mavlinkChannel]; + emit mavlinkMessageStatus(message.sysid, totalSent, _totalReceiveCounter[mavlinkChannel], _totalLossCounter[mavlinkChannel], _runningLossPercent[mavlinkChannel]); + } - if (_message.msgid == MAVLINK_MSG_ID_HEARTBEAT) { - _startLogging(); - mavlink_heartbeat_t heartbeat; - mavlink_msg_heartbeat_decode(&_message, &heartbeat); - emit vehicleHeartbeatInfo(link, _message.sysid, _message.compid, heartbeat.autopilot, heartbeat.type); - } else if (_message.msgid == MAVLINK_MSG_ID_HIGH_LATENCY) { - _startLogging(); - mavlink_high_latency_t highLatency; - mavlink_msg_high_latency_decode(&_message, &highLatency); - // HIGH_LATENCY does not provide autopilot or type information, generic is our safest bet - emit vehicleHeartbeatInfo(link, _message.sysid, _message.compid, MAV_AUTOPILOT_GENERIC, MAV_TYPE_GENERIC); - } else if (_message.msgid == MAVLINK_MSG_ID_HIGH_LATENCY2) { - _startLogging(); - mavlink_high_latency2_t highLatency2; - mavlink_msg_high_latency2_decode(&_message, &highLatency2); - emit vehicleHeartbeatInfo(link, _message.sysid, _message.compid, highLatency2.autopilot, highLatency2.type); - } + emit messageReceived(link, message); -#if 0 - // Given the current state of SiK Radio firmwares there is no way to make the code below work. - // The ArduPilot implementation of SiK Radio firmware always sends MAVLINK_MSG_ID_RADIO_STATUS as a mavlink 1 - // packet even if the vehicle is sending Mavlink 2. - - // Detect if we are talking to an old radio not supporting v2 - mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(mavlinkChannel); - if (_message.msgid == MAVLINK_MSG_ID_RADIO_STATUS && _radio_version_mismatch_count != -1) { - if ((mavlinkStatus->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) - && !(mavlinkStatus->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) { - _radio_version_mismatch_count++; - } - } + if (linkPtr.use_count() == 1) { + return false; + } - if (_radio_version_mismatch_count == 5) { - // Warn the user if the radio continues to send v1 while the link uses v2 - emit protocolStatusMessage(tr("MAVLink Protocol"), tr("Detected radio still using MAVLink v1.0 on a link with MAVLink v2.0 enabled. Please upgrade the radio firmware.")); - // Set to flag warning already shown - _radio_version_mismatch_count = -1; - // Flick link back to v1 - qDebug() << "Switching outbound to mavlink 1.0 due to incoming mavlink 1.0 packet:" << mavlinkStatus << mavlinkChannel << mavlinkStatus->flags; - mavlinkStatus->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1; - } -#endif + return true; +} - // Update MAVLink status on every 32th packet - if ((totalReceiveCounter[mavlinkChannel] & 0x1F) == 0) { - emit mavlinkMessageStatus(_message.sysid, totalSent, totalReceiveCounter[mavlinkChannel], totalLossCounter[mavlinkChannel], receiveLossPercent); - } +void MAVLinkProtocol::_updateVersion(LinkInterface *link, uint8_t mavlinkChannel) +{ + if (link->decodedFirstMavlinkPacket()) { + return; + } - // The packet is emitted as a whole, as it is only 255 - 261 bytes short - // kind of inefficient, but no issue for a groundstation pc. - // It buys as reentrancy for the whole code over all threads - emit messageReceived(link, _message); + link->setDecodedFirstMavlinkPacket(true); + mavlink_status_t *const mavlinkStatus = mavlink_get_channel_status(mavlinkChannel); - // Anyone handling the message could close the connection, which deletes the link, - // so we check if it's expired - if (1 == linkPtr.use_count()) { - break; - } + if (mavlinkStatus->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) { + return; + } - // Reset message parsing - memset(&_status, 0, sizeof(_status)); - memset(&_message, 0, sizeof(_message)); - } + if (mavlinkStatus->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) { + qCDebug(MAVLinkProtocolLog) << "Switching outbound to mavlink 2.0 due to incoming mavlink 2.0 packet:" << mavlinkChannel; + mavlinkStatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1; + setVersion(200); } } -/** - * @return The name of this protocol - **/ -QString MAVLinkProtocol::getName() +void MAVLinkProtocol::_updateCounters(uint8_t mavlinkChannel, const mavlink_message_t &message) { - return tr("MAVLink protocol"); -} + uint8_t lastSeq = _lastIndex[message.sysid][message.compid]; + uint8_t expectedSeq = lastSeq + 1; + _totalReceiveCounter[mavlinkChannel]++; + if (_firstMessage[message.sysid][message.compid] != 0) { + _firstMessage[message.sysid][message.compid] = 0; + lastSeq = message.seq; + expectedSeq = message.seq; + } -/** @return System id of this application */ -int MAVLinkProtocol::getSystemId() const -{ - return systemId; -} + if (message.seq != expectedSeq) { + uint64_t lostMessages = message.seq; + if (lostMessages < expectedSeq) { + lostMessages += 255; + } + lostMessages -= expectedSeq; + _totalLossCounter[mavlinkChannel] += lostMessages; + } -void MAVLinkProtocol::setSystemId(int id) -{ - systemId = id; + _lastIndex[message.sysid][message.compid] = message.seq; + const uint64_t totalSent = _totalReceiveCounter[mavlinkChannel] + _totalLossCounter[mavlinkChannel]; + float receiveLossPercent = static_cast(static_cast(_totalLossCounter[mavlinkChannel]) / static_cast(totalSent)); + receiveLossPercent *= 100.0f; + receiveLossPercent *= 0.5f; + receiveLossPercent += (_runningLossPercent[mavlinkChannel] * 0.5f); + _runningLossPercent[mavlinkChannel] = receiveLossPercent; } -/** @return Component id of this application */ -int MAVLinkProtocol::getComponentId() const +void MAVLinkProtocol::_forward(const mavlink_message_t &message) { - return MAV_COMP_ID_MISSIONPLANNER; + if ((message.msgid == MAVLINK_MSG_ID_SETUP_SIGNING) || !qgcApp()->toolbox()->settingsManager()->appSettings()->forwardMavlink()->rawValue().toBool()) { + return; + } + + SharedLinkInterfacePtr forwardingLink = qgcApp()->toolbox()->linkManager()->mavlinkForwardingLink(); + if (!forwardingLink) { + return; + } + + uint8_t buf[MAVLINK_MAX_PACKET_LEN]{}; + const uint16_t len = mavlink_msg_to_send_buffer(buf, &message); + (void) forwardingLink->writeBytesThreadSafe(reinterpret_cast(buf), len); } -void MAVLinkProtocol::enableVersionCheck(bool enabled) +void MAVLinkProtocol::_forwardSupport(const mavlink_message_t &message) { - _enable_version_check = enabled; - emit versionCheckChanged(enabled); + if ((message.msgid == MAVLINK_MSG_ID_SETUP_SIGNING) || !qgcApp()->toolbox()->linkManager()->mavlinkSupportForwardingEnabled()) { + return; + } + + SharedLinkInterfacePtr forwardingSupportLink = qgcApp()->toolbox()->linkManager()->mavlinkForwardingSupportLink(); + if (!forwardingSupportLink) { + return; + } + + uint8_t buf[MAVLINK_MAX_PACKET_LEN]{}; + const uint16_t len = mavlink_msg_to_send_buffer(buf, &message); + (void) forwardingSupportLink->writeBytesThreadSafe(reinterpret_cast(buf), len); } -void MAVLinkProtocol::_vehicleCountChanged(void) +void MAVLinkProtocol::_logData(LinkInterface *link, const mavlink_message_t &message) { - int count = _multiVehicleManager->vehicles()->count(); - if (count == 0) { - // Last vehicle is gone, close out logging - _stopLogging(); - _radio_version_mismatch_count = 0; + if (!_logSuspendError && !_logSuspendReplay && _tempLogFile->isOpen()) { + const qint64 timestamp = QDateTime::currentMSecsSinceEpoch() * 1000; + uint8_t buf[MAVLINK_MAX_PACKET_LEN + sizeof(timestamp)]; + qToBigEndian(timestamp, buf); + + const qsizetype len = mavlink_msg_to_send_buffer(buf + sizeof(timestamp), &message) + sizeof(timestamp); + const QByteArray log_data(reinterpret_cast(buf), len); + if (_tempLogFile->write(log_data) != len) { + const QString message = QStringLiteral("MAVLink Logging failed. Could not write to file %1, logging disabled.").arg(_tempLogFile->fileName()); + qgcApp()->showAppMessage(message, getName()); + _stopLogging(); + _logSuspendError = true; + } + + if (!_vehicleWasArmed && (message.msgid == MAVLINK_MSG_ID_HEARTBEAT)) { + mavlink_heartbeat_t state; + mavlink_msg_heartbeat_decode(&message, &state); + if (state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY) { + _vehicleWasArmed = true; + } + } + } + + switch (message.msgid) { + case MAVLINK_MSG_ID_HEARTBEAT: { + _startLogging(); + mavlink_heartbeat_t heartbeat; + mavlink_msg_heartbeat_decode(&message, &heartbeat); + emit vehicleHeartbeatInfo(link, message.sysid, message.compid, heartbeat.autopilot, heartbeat.type); + break; + } + case MAVLINK_MSG_ID_HIGH_LATENCY: { + _startLogging(); + mavlink_high_latency_t highLatency; + mavlink_msg_high_latency_decode(&message, &highLatency); + // HIGH_LATENCY does not provide autopilot or type information, generic is our safest bet + emit vehicleHeartbeatInfo(link, message.sysid, message.compid, MAV_AUTOPILOT_GENERIC, MAV_TYPE_GENERIC); + break; + } + case MAVLINK_MSG_ID_HIGH_LATENCY2: { + _startLogging(); + mavlink_high_latency2_t highLatency2; + mavlink_msg_high_latency2_decode(&message, &highLatency2); + emit vehicleHeartbeatInfo(link, message.sysid, message.compid, highLatency2.autopilot, highLatency2.type); + break; + } + default: + break; } } -/// @brief Closes the log file if it is open -bool MAVLinkProtocol::_closeLogFile(void) +bool MAVLinkProtocol::_closeLogFile() { - if (_tempLogFile.isOpen()) { - if (_tempLogFile.size() == 0) { - // Don't save zero byte files - _tempLogFile.remove(); - return false; - } else { - _tempLogFile.flush(); - _tempLogFile.close(); - return true; - } + if (!_tempLogFile->isOpen()) { + return false; + } + + if (_tempLogFile->size() == 0) { + (void) _tempLogFile->remove(); + return false; } - return false; + + (void) _tempLogFile->flush(); + _tempLogFile->close(); + return true; } -void MAVLinkProtocol::_startLogging(void) +void MAVLinkProtocol::_startLogging() { - //-- Are we supposed to write logs? if (qgcApp()->runningUnitTests()) { return; } - AppSettings* appSettings = _app->toolbox()->settingsManager()->appSettings(); - if(appSettings->disableAllPersistence()->rawValue().toBool()) { + + AppSettings *const appSettings = qgcApp()->toolbox()->settingsManager()->appSettings(); + if (appSettings->disableAllPersistence()->rawValue().toBool()) { return; } -#ifdef __mobile__ - //-- Mobile build don't write to /tmp unless told to do so + +#if defined(Q_OS_ANDROID) || defined(Q_OS_IOS) if (!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()) { - emit protocolStatusMessage(tr("MAVLink Protocol"), tr("Opening Flight Data file for writing failed. " - "Unable to write to %1. Please choose a different file location.").arg(_tempLogFile.fileName())); - _closeLogFile(); - _logSuspendError = true; - return; - } - qCDebug(MAVLinkProtocolLog) << "Temp log" << _tempLogFile.fileName(); - emit checkTelemetrySavePath(); + if (_tempLogFile->isOpen()) { + return; + } - _logSuspendError = false; - } + if (_logSuspendReplay) { + return; } + + if (!_tempLogFile->open()) { + const QString message = QStringLiteral("Opening Flight Data file for writing failed. Unable to write to %1. Please choose a different file location.").arg(_tempLogFile->fileName()); + qgcApp()->showAppMessage(message, getName()); + _closeLogFile(); + _logSuspendError = true; + return; + } + + qCDebug(MAVLinkProtocolLog) << "Temp log" << _tempLogFile->fileName(); + (void) _checkTelemetrySavePath(); + + _logSuspendError = false; } -void MAVLinkProtocol::_stopLogging(void) +void MAVLinkProtocol::_stopLogging() { - if (_tempLogFile.isOpen()) { - if (_closeLogFile()) { - if ((_vehicleWasArmed || _app->toolbox()->settingsManager()->appSettings()->telemetrySaveNotArmed()->rawValue().toBool()) && - _app->toolbox()->settingsManager()->appSettings()->telemetrySave()->rawValue().toBool() && - !_app->toolbox()->settingsManager()->appSettings()->disableAllPersistence()->rawValue().toBool()) { - emit saveTelemetryLog(_tempLogFile.fileName()); - } else { - QFile::remove(_tempLogFile.fileName()); - } - } + if (!_tempLogFile->isOpen()) { + return; + } + + if (!_closeLogFile()) { + return; + } + + AppSettings *const appSettings = qgcApp()->toolbox()->settingsManager()->appSettings(); + if ((_vehicleWasArmed || appSettings->telemetrySaveNotArmed()->rawValue().toBool()) && appSettings->telemetrySave()->rawValue().toBool() && !appSettings->disableAllPersistence()->rawValue().toBool()) { + _saveTelemetryLog(_tempLogFile->fileName()); + } else { + (void) QFile::remove(_tempLogFile->fileName()); } + _vehicleWasArmed = false; } -/// @brief Checks the temp directory for log files which may have been left there. -/// This could happen if QGC crashes without the temp log file being saved. -/// Give the user an option to save these orphaned files. -void MAVLinkProtocol::checkForLostLogFiles(void) +void MAVLinkProtocol::checkForLostLogFiles() { - QDir tempDir(QStandardPaths::writableLocation(QStandardPaths::TempLocation)); + static const QDir tempDir(QStandardPaths::writableLocation(QStandardPaths::TempLocation)); + static const QString filter(QStringLiteral("*.%1").arg(_logFileExtension)); - QString filter(QString("*.%1").arg(_logFileExtension)); - QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files); - //qDebug() << "Orphaned log file count" << fileInfoList.count(); + const QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files); + qCDebug(MAVLinkProtocolLog) << "Orphaned log file count" << fileInfoList.count(); - for(const QFileInfo& fileInfo: fileInfoList) { - //qDebug() << "Orphaned log file" << fileInfo.filePath(); + for (const QFileInfo &fileInfo: fileInfoList) { + qCDebug(MAVLinkProtocolLog) << "Orphaned log file" << fileInfo.filePath(); if (fileInfo.size() == 0) { - // Delete all zero length files - QFile::remove(fileInfo.filePath()); + (void) QFile::remove(fileInfo.filePath()); continue; } - emit saveTelemetryLog(fileInfo.filePath()); + _saveTelemetryLog(fileInfo.filePath()); + } +} + +void MAVLinkProtocol::deleteTempLogFiles() +{ + static const QDir tempDir(QStandardPaths::writableLocation(QStandardPaths::TempLocation)); + static const QString filter(QStringLiteral("*.%1").arg(_logFileExtension)); + + const QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files); + qCDebug(MAVLinkProtocolLog) << "Temp log file count" << fileInfoList.count(); + + for (const QFileInfo &fileInfo: fileInfoList) { + qCDebug(MAVLinkProtocolLog) << "Temp log file" << fileInfo.filePath(); + (void) QFile::remove(fileInfo.filePath()); } } -void MAVLinkProtocol::suspendLogForReplay(bool suspend) +void MAVLinkProtocol::_saveTelemetryLog(const QString &tempLogfile) { - _logSuspendReplay = suspend; + if (_checkTelemetrySavePath()) { + const QString saveDirPath = qgcApp()->toolbox()->settingsManager()->appSettings()->telemetrySavePath(); + const QDir saveDir(saveDirPath); + + const QString nameFormat("%1%2.%3"); + const QString dtFormat("yyyy-MM-dd hh-mm-ss"); + + int tryIndex = 1; + QString saveFileName = nameFormat.arg(QDateTime::currentDateTime().toString(dtFormat), QStringLiteral(""), AppSettings::telemetryFileExtension); + while (saveDir.exists(saveFileName)) { + saveFileName = nameFormat.arg(QDateTime::currentDateTime().toString(dtFormat), QStringLiteral(".%1").arg(tryIndex++), AppSettings::telemetryFileExtension); + } + + const QString saveFilePath = saveDir.absoluteFilePath(saveFileName); + QFile tempFile(tempLogfile); + if (!tempFile.copy(saveFilePath)) { + const QString error = tr("Unable to save telemetry log. Error copying telemetry to '%1': '%2'.").arg(saveFilePath, tempFile.errorString()); + qgcApp()->showAppMessage(error); + } + } + + (void) QFile::remove(tempLogfile); } -void MAVLinkProtocol::deleteTempLogFiles(void) +bool MAVLinkProtocol::_checkTelemetrySavePath() { - QDir tempDir(QStandardPaths::writableLocation(QStandardPaths::TempLocation)); + const QString saveDirPath = qgcApp()->toolbox()->settingsManager()->appSettings()->telemetrySavePath(); + if (saveDirPath.isEmpty()) { + const QString error = tr("Unable to save telemetry log. Application save directory is not set."); + qgcApp()->showAppMessage(error); + return false; + } + + const QDir saveDir(saveDirPath); + if (!saveDir.exists()) { + const QString error = tr("Unable to save telemetry log. Telemetry save directory \"%1\" does not exist.").arg(saveDirPath); + qgcApp()->showAppMessage(error); + return false; + } + + return true; +} - QString filter(QString("*.%1").arg(_logFileExtension)); - QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files); +void MAVLinkProtocol::setSystemId(int id) +{ + if (id != _systemId) { + _systemId = id; + emit systemIdChanged(_systemId); + } +} - for (const QFileInfo& fileInfo: fileInfoList) { - QFile::remove(fileInfo.filePath()); +void MAVLinkProtocol::enableVersionCheck(bool enabled) +{ + if (enabled != _enableVersionCheck) { + _enableVersionCheck = enabled; + emit versionCheckChanged(enabled); } } +void MAVLinkProtocol::_vehicleCountChanged() +{ + if (qgcApp()->toolbox()->multiVehicleManager()->vehicles()->count() == 0) { + _stopLogging(); + } +} diff --git a/src/Comms/MAVLinkProtocol.h b/src/Comms/MAVLinkProtocol.h index 5f6d5968d8d..e761f6a651e 100644 --- a/src/Comms/MAVLinkProtocol.h +++ b/src/Comms/MAVLinkProtocol.h @@ -9,160 +9,141 @@ #pragma once -#include "LinkInterface.h" -#include "QGCMAVLink.h" -#include "QGCTemporaryFile.h" -#include "QGCToolbox.h" - -#include #include #include +#include +#include -class LinkManager; -class MultiVehicleManager; -class QGCApplication; +#include "LinkInterface.h" +#include "MAVLinkLib.h" + +class QGCTemporaryFile; Q_DECLARE_LOGGING_CATEGORY(MAVLinkProtocolLog) -/** - * @brief MAVLink micro air vehicle protocol reference implementation. - * - * MAVLink is a generic communication protocol for micro air vehicles. - * for more information, please see the official website: https://mavlink.io - **/ -class MAVLinkProtocol : public QGCTool +/// MAVLink micro air vehicle protocol reference implementation. +/// MAVLink is a generic communication protocol for micro air vehicles. +/// for more information, please see the official website: https://mavlink.io +class MAVLinkProtocol : public QObject { Q_OBJECT public: - MAVLinkProtocol(QGCApplication* app, QGCToolbox* toolbox); - ~MAVLinkProtocol(); - - /** @brief Get the human-friendly name of this protocol */ - QString getName(); - /** @brief Get the system id of this application */ - int getSystemId() const; - /** @brief Get the component id of this application */ - int getComponentId() const; - - /** @brief Get protocol version check state */ - bool versionCheckEnabled() const { - return _enable_version_check; - } - /** @brief Get the protocol version */ - int getVersion() { - return MAVLINK_VERSION; - } - /** @brief Get the currently configured protocol version */ - unsigned getCurrentVersion() const{ - return _current_version; - } - /** - * Reset the counters for all metadata for this link. - */ - virtual void resetMetadataForLink(LinkInterface *link); + /// Constructs an MAVLinkProtocol object. + /// @param parent The parent QObject. + explicit MAVLinkProtocol(QObject *parent = nullptr); - /// Suspend/Restart logging during replay. - void suspendLogForReplay(bool suspend); - - /// Set protocol version - void setVersion(unsigned version); + /// Destructor for the MAVLinkProtocol class. + ~MAVLinkProtocol(); - // Override from QGCTool - virtual void setToolbox(QGCToolbox *toolbox); + /// Gets the singleton instance of MAVLinkProtocol. + /// @return The singleton instance. + static MAVLinkProtocol *instance(); -public slots: - /** @brief Receive bytes from a communication interface */ - void receiveBytes(LinkInterface* link, QByteArray b); + /// Get the human-friendly name of this protocol + static QString getName() { return QStringLiteral("MAVLink protocol"); } - /** @brief Log bytes sent from a communication interface */ - void logSentBytes(LinkInterface* link, QByteArray b); + /// Get the system id of this application + int getSystemId() const { return _systemId; } - /** @brief Set the system id of this application */ - void setSystemId(int id); + /// Get the component id of this application + static int getComponentId() { return MAV_COMP_ID_MISSIONPLANNER; } - /** @brief Enable / disable version check */ - void enableVersionCheck(bool enabled); + /// Get protocol version check state + bool versionCheckEnabled() const { return _enableVersionCheck; } - /** @brief Load protocol settings */ - void loadSettings(); - /** @brief Store protocol settings */ - void storeSettings(); + /// Get the protocol version + static int getVersion() { return MAVLINK_VERSION; } - /// @brief Deletes any log files which are in the temp directory - static void deleteTempLogFiles(void); + /// Get the currently configured protocol version + unsigned getCurrentVersion() const { return _currentVersion; } - /// Checks for lost log files - void checkForLostLogFiles(void); + /// Reset the counters for all metadata for this link. + void resetMetadataForLink(LinkInterface *link); -protected: - bool _enable_version_check; ///< Enable checking of version match of MAV and QGC - uint8_t lastIndex[256][256]; ///< Store the last received sequence ID for each system/componenet pair - uint8_t firstMessage[256][256]; ///< First message flag - uint64_t totalReceiveCounter[MAVLINK_COMM_NUM_BUFFERS]; ///< The total number of successfully received messages - uint64_t totalLossCounter[MAVLINK_COMM_NUM_BUFFERS]; ///< Total messages lost during transmission. - float runningLossPercent[MAVLINK_COMM_NUM_BUFFERS]; ///< Loss rate + /// Suspend/Restart logging during replay. + void suspendLogForReplay(bool suspend) { _logSuspendReplay = suspend; } - mavlink_message_t _message; - mavlink_status_t _status; + /// Set protocol version + void setVersion(unsigned version); - bool versionMismatchIgnore; - int systemId; - unsigned _current_version; - int _radio_version_mismatch_count; + /// Checks the temp directory for log files which may have been left there. + /// This could happen if QGC crashes without the temp log file being saved. + /// Give the user an option to save these orphaned files. + void checkForLostLogFiles(); signals: /// Heartbeat received on link - void vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType); + void vehicleHeartbeatInfo(LinkInterface *link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType); - /** @brief Message received and directly copied via signal */ - void messageReceived(LinkInterface* link, mavlink_message_t message); - /** @brief Emitted if version check is enabled / disabled */ + /// Message received and directly copied via signal + void messageReceived(LinkInterface *link, const mavlink_message_t &message); + + /// Emitted if version check is enabled/disabled void versionCheckChanged(bool enabled); - /** @brief Emitted if a message from the protocol should reach the user */ - void protocolStatusMessage(const QString& title, const QString& message); - /** @brief Emitted if a new system ID was set */ + + /// Emitted if a new system ID was set void systemIdChanged(int systemId); - void mavlinkMessageStatus(int uasId, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent); + void mavlinkMessageStatus(int sysid, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent); - /** - * @brief Emitted if a new radio status packet received - * - * @param rxerrors receive errors - * @param fixed count of error corrected packets - * @param rssi local signal strength in dBm - * @param remrssi remote signal strength in dBm - * @param txbuf how full the tx buffer is as a percentage - * @param noise background noise level - * @param remnoise remote background noise level - */ - void radioStatusChanged(LinkInterface* link, unsigned rxerrors, unsigned fixed, int rssi, int remrssi, - unsigned txbuf, unsigned noise, unsigned remnoise); +public slots: + /// Receive bytes from a communication interface and constructs a MAVLink packet + /// @param link The interface to read from + void receiveBytes(LinkInterface *link, const QByteArray &data); + + /// Log bytes sent from a communication interface and logs a MAVLink packet. + /// It can handle multiple links in parallel, as each link has it's own buffer/parsing state machine. + /// @param link The interface to read from + void logSentBytes(const LinkInterface *link, const QByteArray &data); - /// Emitted when a temporary telemetry log file is ready for saving - void saveTelemetryLog(QString tempLogfile); + /// Set the system id of this application + void setSystemId(int id); - /// Emitted when a telemetry log is started to save. - void checkTelemetrySavePath(void); + /// Enable/Disable version check + void enableVersionCheck(bool enabled); + + /// Deletes any log files which are in the temp directory + static void deleteTempLogFiles(); private slots: - void _vehicleCountChanged(void); + void _vehicleCountChanged(); private: - bool _closeLogFile(void); - void _startLogging(void); - void _stopLogging(void); + void _logData(LinkInterface *link, const mavlink_message_t &message); + bool _closeLogFile(); + void _startLogging(); + void _stopLogging(); - bool _logSuspendError; ///< true: Logging suspended due to error - bool _logSuspendReplay; ///< true: Logging suspended due to replay - bool _vehicleWasArmed; ///< true: Vehicle was armed during log sequence + void _forward(const mavlink_message_t &message); + void _forwardSupport(const mavlink_message_t &message); - QGCTemporaryFile _tempLogFile; ///< File to log to - static constexpr const char* _tempLogFileTemplate = "FlightDataXXXXXX"; ///< Template for temporary log file - static constexpr const char* _logFileExtension = "mavlink"; ///< Extension for log files + void _updateCounters(uint8_t mavlinkChannel, const mavlink_message_t &message); + bool _updateStatus(LinkInterface *link, const SharedLinkInterfacePtr linkPtr, uint8_t mavlinkChannel, const mavlink_message_t &message); + void _updateVersion(LinkInterface *link, uint8_t mavlinkChannel); - LinkManager* _linkMgr; - MultiVehicleManager* _multiVehicleManager; -}; + void _saveTelemetryLog(const QString &tempLogfile); + bool _checkTelemetrySavePath(); + + void _storeSettings() const; + void _loadSettings(); + + QGCTemporaryFile * const _tempLogFile = nullptr; + bool _logSuspendError = false; ///< true: Logging suspended due to error + bool _logSuspendReplay = false; ///< true: Logging suspended due to replay + bool _vehicleWasArmed = false; ///< true: Vehicle was armed during log sequence + + bool _enableVersionCheck = true; ///< Enable checking of version match of MAV and QGC + uint8_t _lastIndex[256][256]{}; ///< Store the last received sequence ID for each system/componenet pair + uint8_t _firstMessage[256][256]{}; ///< First message flag + uint64_t _totalReceiveCounter[MAVLINK_COMM_NUM_BUFFERS]{}; ///< The total number of successfully received messages + uint64_t _totalLossCounter[MAVLINK_COMM_NUM_BUFFERS]{}; ///< Total messages lost during transmission. + float _runningLossPercent[MAVLINK_COMM_NUM_BUFFERS]{}; ///< Loss rate + + int _systemId = 255; + unsigned _currentVersion = 100; + + static constexpr const char *_tempLogFileTemplate = "FlightDataXXXXXX"; ///< Template for temporary log file + static constexpr const char *_logFileExtension = "mavlink"; ///< Extension for log files +}; diff --git a/src/Comms/MockLink/MockLink.cc b/src/Comms/MockLink/MockLink.cc index 84a133f77d4..b485ba5b2c4 100644 --- a/src/Comms/MockLink/MockLink.cc +++ b/src/Comms/MockLink/MockLink.cc @@ -11,6 +11,7 @@ #include "QGCLoggingCategory.h" #include "QGCApplication.h" #include "LinkManager.h" +#include "MAVLinkProtocol.h" #include "QGCLoggingCategory.h" #include @@ -45,7 +46,7 @@ static_assert(LinkManager::invalidMavlinkChannel() == std::numeric_limitstoolbox()->mavlinkProtocol()) + , _missionItemHandler (this, MAVLinkProtocol::instance()) , _name ("MockLink") , _connected (false) , _vehicleComponentId (MAV_COMP_ID_AUTOPILOT1) diff --git a/src/FactSystem/ParameterManager.cc b/src/FactSystem/ParameterManager.cc index 1cc25f36d25..11d5e49d92a 100644 --- a/src/FactSystem/ParameterManager.cc +++ b/src/FactSystem/ParameterManager.cc @@ -73,7 +73,6 @@ const QHash _mavlinkCompIdHash { ParameterManager::ParameterManager(Vehicle* vehicle) : QObject (vehicle) , _vehicle (vehicle) - , _mavlink (nullptr) , _loadProgress (0.0) , _parametersReady (false) , _missingParameters (false) @@ -96,8 +95,6 @@ ParameterManager::ParameterManager(Vehicle* vehicle) return; } - _mavlink = qgcApp()->toolbox()->mavlinkProtocol(); - _initialRequestTimeoutTimer.setSingleShot(true); _initialRequestTimeoutTimer.setInterval(5000); connect(&_initialRequestTimeoutTimer, &QTimer::timeout, this, &ParameterManager::_initialRequestTimeout); @@ -560,11 +557,10 @@ void ParameterManager::refreshAllParameters(uint8_t componentId) _waitingReadParamIndexMap[cid][waitingIndex] = 0; } } - MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); mavlink_message_t msg; - mavlink_msg_param_request_list_pack_chan(mavlink->getSystemId(), - mavlink->getComponentId(), + mavlink_msg_param_request_list_pack_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, _vehicle->id(), @@ -805,8 +801,8 @@ void ParameterManager::_readParameterRaw(int componentId, const QString& paramNa strncpy(fixedParamName, paramName.toStdString().c_str(), sizeof(fixedParamName)); - mavlink_msg_param_request_read_pack_chan(_mavlink->getSystemId(), // QGC system id - _mavlink->getComponentId(), // QGC component id + mavlink_msg_param_request_read_pack_chan(MAVLinkProtocol::instance()->getSystemId(), // QGC system id + MAVLinkProtocol::instance()->getComponentId(), // QGC component id sharedLink->mavlinkChannel(), &msg, // Pack into this mavlink_message_t _vehicle->id(), // Target system id @@ -869,8 +865,8 @@ void ParameterManager::_sendParamSetToVehicle(int componentId, const QString& pa strncpy(p.param_id, paramName.toStdString().c_str(), sizeof(p.param_id)); mavlink_message_t msg; - mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(), - _mavlink->getComponentId(), + mavlink_msg_param_set_encode_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, &p); @@ -967,8 +963,8 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian p.target_system = (uint8_t)_vehicle->id(); p.target_component = (uint8_t)componentId; mavlink_message_t msg; - mavlink_msg_param_set_encode_chan(_mavlink->getSystemId(), - _mavlink->getComponentId(), + mavlink_msg_param_set_encode_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, &p); diff --git a/src/FactSystem/ParameterManager.h b/src/FactSystem/ParameterManager.h index 7a09d4c991a..3f135db0954 100644 --- a/src/FactSystem/ParameterManager.h +++ b/src/FactSystem/ParameterManager.h @@ -26,7 +26,6 @@ Q_DECLARE_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog) class ParameterEditorController; class Vehicle; -class MAVLinkProtocol; class ParameterManager : public QObject { @@ -136,7 +135,6 @@ private slots: static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false); Vehicle* _vehicle; - MAVLinkProtocol* _mavlink; QMap> _mapCompId2FactMap; diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 5e7f3d76007..f0856c09e27 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -874,10 +874,9 @@ void APMFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu cmd.y = 0.0f; cmd.z = static_cast(-(altitudeChange)); - MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); mavlink_msg_set_position_target_local_ned_encode_chan( - static_cast(mavlink->getSystemId()), - static_cast(mavlink->getComponentId()), + static_cast(MAVLinkProtocol::instance()->getSystemId()), + static_cast(MAVLinkProtocol::instance()->getComponentId()), sharedLink->mavlinkChannel(), &msg, &cmd); @@ -1083,10 +1082,9 @@ void APMFirmwarePlugin::_handleRCChannels(Vehicle* vehicle, mavlink_message_t* m if(channels.rssi && channels.rssi != 255) { channels.rssi = static_cast(static_cast(channels.rssi) / 254.0 * 100.0); } - MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); mavlink_msg_rc_channels_encode_chan( - static_cast(mavlink->getSystemId()), - static_cast(mavlink->getComponentId()), + static_cast(MAVLinkProtocol::instance()->getSystemId()), + static_cast(MAVLinkProtocol::instance()->getComponentId()), sharedLink->mavlinkChannel(), message, &channels); @@ -1104,10 +1102,9 @@ void APMFirmwarePlugin::_handleRCChannelsRaw(Vehicle* vehicle, mavlink_message_t if(channels.rssi) { channels.rssi = static_cast(static_cast(channels.rssi) / 255.0 * 100.0); } - MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); mavlink_msg_rc_channels_raw_encode_chan( - static_cast(mavlink->getSystemId()), - static_cast(mavlink->getComponentId()), + static_cast(MAVLinkProtocol::instance()->getSystemId()), + static_cast(MAVLinkProtocol::instance()->getComponentId()), sharedLink->mavlinkChannel(), message, &channels); @@ -1142,7 +1139,6 @@ void APMFirmwarePlugin::sendGCSMotionReport(Vehicle *vehicle, FollowMe::GCSMotio return; } - const MAVLinkProtocol* const mavlinkProtocol = qgcApp()->toolbox()->mavlinkProtocol(); const mavlink_global_position_int_t globalPositionInt = { static_cast(qgcApp()->msecsSinceBoot()), /*< [ms] Timestamp (time since system boot).*/ motionReport.lat_int, /*< [degE7] Latitude, expressed*/ @@ -1157,8 +1153,8 @@ void APMFirmwarePlugin::sendGCSMotionReport(Vehicle *vehicle, FollowMe::GCSMotio mavlink_message_t message; (void) mavlink_msg_global_position_int_encode_chan( - static_cast(mavlinkProtocol->getSystemId()), - static_cast(mavlinkProtocol->getComponentId()), + static_cast(MAVLinkProtocol::instance()->getSystemId()), + static_cast(MAVLinkProtocol::instance()->getComponentId()), sharedLink->mavlinkChannel(), &message, &globalPositionInt diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc index 3b679706874..1f4a584dfb9 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.cc +++ b/src/FirmwarePlugin/FirmwarePlugin.cc @@ -540,7 +540,6 @@ void FirmwarePlugin::sendGCSMotionReport(Vehicle *vehicle, FollowMe::GCSMotionRe return; } - const MAVLinkProtocol* const mavlinkProtocol = qgcApp()->toolbox()->mavlinkProtocol(); mavlink_follow_target_t follow_target{0}; follow_target.timestamp = qgcApp()->msecsSinceBoot(); @@ -555,8 +554,8 @@ void FirmwarePlugin::sendGCSMotionReport(Vehicle *vehicle, FollowMe::GCSMotionRe mavlink_message_t message; mavlink_msg_follow_target_encode_chan( - static_cast(mavlinkProtocol->getSystemId()), - static_cast(mavlinkProtocol->getComponentId()), + static_cast(MAVLinkProtocol::instance()->getSystemId()), + static_cast(MAVLinkProtocol::instance()->getComponentId()), sharedLink->mavlinkChannel(), &message, &follow_target diff --git a/src/GPS/RTCMMavlink.cc b/src/GPS/RTCMMavlink.cc index b9ae04dd54c..9a9fc130099 100644 --- a/src/GPS/RTCMMavlink.cc +++ b/src/GPS/RTCMMavlink.cc @@ -71,11 +71,10 @@ void RTCMMavlink::_sendMessageToVehicle(const mavlink_gps_rtcm_data_t &data) Vehicle* const vehicle = qobject_cast(vehicles->get(i)); const SharedLinkInterfacePtr sharedLink = vehicle->vehicleLinkManager()->primaryLink().lock(); if (sharedLink) { - const MAVLinkProtocol* const mavlinkProtocol = qgcApp()->toolbox()->mavlinkProtocol(); mavlink_message_t message; (void) mavlink_msg_gps_rtcm_data_encode_chan( - mavlinkProtocol->getSystemId(), - mavlinkProtocol->getComponentId(), + MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &message, &data diff --git a/src/MAVLink/QGCMAVLink.cc b/src/MAVLink/QGCMAVLink.cc index bb61af2b191..76b0e11b11e 100644 --- a/src/MAVLink/QGCMAVLink.cc +++ b/src/MAVLink/QGCMAVLink.cc @@ -8,8 +8,7 @@ ****************************************************************************/ #include "QGCMAVLink.h" -#include "MAVLinkLib.h" -#include +#include "QGCLoggingCategory.h" #include @@ -38,6 +37,10 @@ QGCMAVLink::QGCMAVLink(QObject *parent) : QObject(parent) { // qCDebug(StatusTextHandlerLog) << Q_FUNC_INFO << this; + + qRegisterMetaType("mavlink_message_t"); + qRegisterMetaType("MAV_TYPE"); + qRegisterMetaType("MAV_AUTOPILOT"); } QGCMAVLink::~QGCMAVLink() diff --git a/src/MAVLink/QGCMAVLink.h b/src/MAVLink/QGCMAVLink.h index ad345a9c1fc..cf4da6f6762 100644 --- a/src/MAVLink/QGCMAVLink.h +++ b/src/MAVLink/QGCMAVLink.h @@ -9,15 +9,18 @@ #pragma once -#include -#include #include #include +#include +#include #include #include "MAVLinkLib.h" Q_DECLARE_LOGGING_CATEGORY(QGCMAVLinkLog) +// Q_DECLARE_METATYPE(mavlink_message_t) +Q_DECLARE_METATYPE(MAV_TYPE) +Q_DECLARE_METATYPE(MAV_AUTOPILOT) // TODO: Q_NAMESPACE class QGCMAVLink : public QObject diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc index c302b2eedf5..99bde67de50 100644 --- a/src/MissionManager/MissionManager.cc +++ b/src/MissionManager/MissionManager.cc @@ -83,8 +83,8 @@ void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoC missionItem.current = altChangeOnly ? 3 : 2; missionItem.autocontinue = true; - mavlink_msg_mission_item_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), + mavlink_msg_mission_item_encode_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &messageOut, &missionItem); diff --git a/src/MissionManager/PlanManager.cc b/src/MissionManager/PlanManager.cc index 3dcd9d25314..2631b605692 100644 --- a/src/MissionManager/PlanManager.cc +++ b/src/MissionManager/PlanManager.cc @@ -107,8 +107,8 @@ void PlanManager::_writeMissionCount(void) mavlink_message_t message; mavlink_msg_mission_count_pack_chan( - qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), + MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &message, _vehicle->id(), @@ -153,8 +153,8 @@ void PlanManager::_requestList(void) SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock(); if (sharedLink){ mavlink_message_t message; - mavlink_msg_mission_request_list_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), + mavlink_msg_mission_request_list_pack_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &message, _vehicle->id(), @@ -296,8 +296,8 @@ void PlanManager::_readTransactionComplete(void) mavlink_message_t message; mavlink_msg_mission_ack_pack_chan( - qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), + MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &message, _vehicle->id(), @@ -359,8 +359,8 @@ void PlanManager::_requestNextMissionItem(void) if (sharedLink) { mavlink_message_t message; - mavlink_msg_mission_request_int_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), + mavlink_msg_mission_request_int_pack_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &message, _vehicle->id(), @@ -528,8 +528,8 @@ void PlanManager::_handleMissionRequest(const mavlink_message_t& message) if (sharedLink) { mavlink_message_t messageOut; - mavlink_msg_mission_item_int_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), + mavlink_msg_mission_item_int_pack_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &messageOut, _vehicle->id(), @@ -878,8 +878,8 @@ void PlanManager::_removeAllWorker(void) if (sharedLink) { mavlink_message_t message; - mavlink_msg_mission_clear_all_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), + mavlink_msg_mission_clear_all_pack_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &message, _vehicle->id(), diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 8be96a39137..71dab30c4b6 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -90,6 +90,11 @@ static QObject* shapeFileHelperSingletonFactory(QQmlEngine*, QJSEngine*) return new ShapeFileHelper; } +static QObject *mavlinkSingletonFactory(QQmlEngine*, QJSEngine*) +{ + return new QGCMAVLink(); +} + QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) : QApplication(argc, argv) , _runningUnitTests(unitTesting) @@ -293,6 +298,8 @@ void QGCApplication::init() qmlRegisterSingletonType("QGroundControl.ShapeFileHelper", 1, 0, "ShapeFileHelper", shapeFileHelperSingletonFactory); + qmlRegisterSingletonType("MAVLink", 1, 0, "MAVLink", mavlinkSingletonFactory); + // Although this should really be in _initForNormalAppBoot putting it here allowws us to create unit tests which pop up more easily if(QFontDatabase::addApplicationFont(":/fonts/opensans") < 0) { @@ -363,8 +370,7 @@ void QGCApplication::_initForNormalAppBoot() #endif // Now that main window is up check for lost log files - connect(this, &QGCApplication::checkForLostLogFiles, _toolbox->mavlinkProtocol(), &MAVLinkProtocol::checkForLostLogFiles); - emit checkForLostLogFiles(); + MAVLinkProtocol::instance()->checkForLostLogFiles(); // Load known link configurations _toolbox->linkManager()->loadLinkConfigurationList(); @@ -408,60 +414,6 @@ void QGCApplication::criticalMessageBoxOnMainThread(const QString& /*title*/, co showAppMessage(msg); } -void QGCApplication::saveTelemetryLogOnMainThread(const 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 */)) { - - const QString saveDirPath = _toolbox->settingsManager()->appSettings()->telemetrySavePath(); - const QDir saveDir(saveDirPath); - - const QString nameFormat("%1%2.%3"); - const QString dtFormat("yyyy-MM-dd hh-mm-ss"); - - int tryIndex = 1; - QString saveFileName = nameFormat.arg( - QDateTime::currentDateTime().toString(dtFormat)).arg(QStringLiteral("")).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); - } - const QString saveFilePath = saveDir.absoluteFilePath(saveFileName); - - QFile tempFile(tempLogfile); - if (!tempFile.copy(saveFilePath)) { - const QString error = tr("Unable to save telemetry log. Error copying telemetry to '%1': '%2'.").arg(saveFilePath).arg(tempFile.errorString()); - showAppMessage(error); - } - } - QFile::remove(tempLogfile); -} - -void QGCApplication::checkTelemetrySavePathOnMainThread() -{ - // This is called with an active vehicle so don't pop message boxes which holds ui thread - _checkTelemetrySavePath(false /* useMessageBox */); -} - -bool QGCApplication::_checkTelemetrySavePath(bool /*useMessageBox*/) -{ - const QString saveDirPath = _toolbox->settingsManager()->appSettings()->telemetrySavePath(); - if (saveDirPath.isEmpty()) { - const QString error = tr("Unable to save telemetry log. Application save directory is not set."); - showAppMessage(error); - return false; - } - - const QDir saveDir(saveDirPath); - if (!saveDir.exists()) { - const QString error = tr("Unable to save telemetry log. Telemetry save directory \"%1\" does not exist.").arg(saveDirPath); - showAppMessage(error); - return false; - } - - return true; -} - void QGCApplication::reportMissingParameter(int componentId, const QString& name) { const QPair missingParam(componentId, name); diff --git a/src/QGCApplication.h b/src/QGCApplication.h index 420b4ca7f46..9ce9a110d2f 100644 --- a/src/QGCApplication.h +++ b/src/QGCApplication.h @@ -116,12 +116,6 @@ public slots: void qmlAttemptWindowClose(); - /// Save the specified telemetry Log - void saveTelemetryLogOnMainThread(const QString &tempLogfile); - - /// Check that the telemetry save path is set correctly - void checkTelemetrySavePathOnMainThread(); - /// Get current language const QLocale getCurrentLanguage() { return _locale; } @@ -138,11 +132,7 @@ public slots: QGCImageProvider* qgcImageProvider(); signals: - /// This is connected to MAVLinkProtocol::checkForLostLogFiles. We signal this to ourselves to call the slot - /// on the MAVLinkProtocol thread; - void checkForLostLogFiles (); - - void languageChanged (const QLocale locale); + void languageChanged(const QLocale locale); public: /// @brief Perform initialize which is common to both normal application running and unit tests. @@ -164,7 +154,6 @@ private slots: QObject* _rootQmlObject(); void _checkForNewVersion(); - bool _checkTelemetrySavePath(bool useMessageBox); // Overrides from QApplication bool compressEvent(QEvent *event, QObject *receiver, QPostEventList *postedEvents) override; diff --git a/src/QGCToolbox.cc b/src/QGCToolbox.cc index 0f7338c5338..7a228d85fb1 100644 --- a/src/QGCToolbox.cc +++ b/src/QGCToolbox.cc @@ -9,7 +9,6 @@ #include "LinkManager.h" -#include "MAVLinkProtocol.h" #include "MultiVehicleManager.h" #include "QGCCorePlugin.h" #include "SettingsManager.h" @@ -28,7 +27,6 @@ QGCToolbox::QGCToolbox(QGCApplication* app) //-- Scan and load plugins _scanAndLoadPlugins(app); _linkManager = new LinkManager (app, this); - _mavlinkProtocol = new MAVLinkProtocol (app, this); _multiVehicleManager = new MultiVehicleManager (app, this); } @@ -39,7 +37,6 @@ void QGCToolbox::setChildToolboxes(void) _corePlugin->setToolbox(this); _linkManager->setToolbox(this); - _mavlinkProtocol->setToolbox(this); _multiVehicleManager->setToolbox(this); } diff --git a/src/QGCToolbox.h b/src/QGCToolbox.h index 5327a7491e8..2ca2aa23436 100644 --- a/src/QGCToolbox.h +++ b/src/QGCToolbox.h @@ -14,7 +14,6 @@ #include class LinkManager; -class MAVLinkProtocol; class MultiVehicleManager; class QGCApplication; class QGCCorePlugin; @@ -28,7 +27,6 @@ class QGCToolbox : public QObject { QGCToolbox(QGCApplication* app); LinkManager* linkManager () { return _linkManager; } - MAVLinkProtocol* mavlinkProtocol () { return _mavlinkProtocol; } MultiVehicleManager* multiVehicleManager () { return _multiVehicleManager; } QGCCorePlugin* corePlugin () { return _corePlugin; } SettingsManager* settingsManager () { return _settingsManager; } @@ -38,7 +36,6 @@ class QGCToolbox : public QObject { void _scanAndLoadPlugins(QGCApplication *app); LinkManager* _linkManager = nullptr; - MAVLinkProtocol* _mavlinkProtocol = nullptr; MultiVehicleManager* _multiVehicleManager = nullptr; QGCCorePlugin* _corePlugin = nullptr; SettingsManager* _settingsManager = nullptr; diff --git a/src/QmlControls/QGroundControlQmlGlobal.cc b/src/QmlControls/QGroundControlQmlGlobal.cc index 0000167b4da..f9ee2722e10 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.cc +++ b/src/QmlControls/QGroundControlQmlGlobal.cc @@ -268,13 +268,13 @@ void QGroundControlQmlGlobal::stopOneMockLink(void) void QGroundControlQmlGlobal::setIsVersionCheckEnabled(bool enable) { - _toolbox->mavlinkProtocol()->enableVersionCheck(enable); + MAVLinkProtocol::instance()->enableVersionCheck(enable); emit isVersionCheckEnabledChanged(enable); } void QGroundControlQmlGlobal::setMavlinkSystemID(int id) { - _toolbox->mavlinkProtocol()->setSystemId(id); + MAVLinkProtocol::instance()->setSystemId(id); emit mavlinkSystemIDChanged(id); } @@ -397,12 +397,12 @@ QString QGroundControlQmlGlobal::altitudeModeShortDescription(AltMode altMode) bool QGroundControlQmlGlobal::isVersionCheckEnabled() { - return _toolbox->mavlinkProtocol()->versionCheckEnabled(); + return MAVLinkProtocol::instance()->versionCheckEnabled(); } int QGroundControlQmlGlobal::mavlinkSystemID() { - return _toolbox->mavlinkProtocol()->getSystemId(); + return MAVLinkProtocol::instance()->getSystemId(); } QString QGroundControlQmlGlobal::elevationProviderName() diff --git a/src/Vehicle/FTPManager.cc b/src/Vehicle/FTPManager.cc index 6ca95bbda43..924da502cfc 100644 --- a/src/Vehicle/FTPManager.cc +++ b/src/Vehicle/FTPManager.cc @@ -11,6 +11,7 @@ #include "MAVLinkProtocol.h" #include "Vehicle.h" #include "QGCApplication.h" +#include "QGCToolbox.h" #include "QGCLoggingCategory.h" #include @@ -230,7 +231,7 @@ void FTPManager::_mavlinkMessageReceived(const mavlink_message_t& message) mavlink_msg_file_transfer_protocol_decode(&message, &data); // Make sure we are the target system - int qgcId = qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(); + int qgcId = MAVLinkProtocol::instance()->getSystemId(); if (data.target_system != qgcId) { return; } @@ -738,8 +739,8 @@ void FTPManager::_sendRequestExpectAck(MavlinkFTP::Request* request) qCDebug(FTPManagerLog) << "_sendRequestExpectAck opcode:" << MavlinkFTP::opCodeToString(static_cast(request->hdr.opcode)) << "seqNumber:" << request->hdr.seqNumber; mavlink_message_t message; - mavlink_msg_file_transfer_protocol_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), + mavlink_msg_file_transfer_protocol_pack_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &message, 0, // Target network, 0=broadcast? diff --git a/src/Vehicle/MultiVehicleManager.cc b/src/Vehicle/MultiVehicleManager.cc index 7ee21437fff..5c53e7dd208 100644 --- a/src/Vehicle/MultiVehicleManager.cc +++ b/src/Vehicle/MultiVehicleManager.cc @@ -36,7 +36,6 @@ MultiVehicleManager::MultiVehicleManager(QGCApplication* app, QGCToolbox* toolbo , _parameterReadyVehicleAvailable(false) , _activeVehicle(nullptr) , _offlineEditingVehicle(nullptr) - , _mavlinkProtocol(nullptr) , _gcsHeartbeatEnabled(true) { QSettings settings; @@ -49,8 +48,6 @@ void MultiVehicleManager::setToolbox(QGCToolbox *toolbox) { QGCTool::setToolbox(toolbox); - _mavlinkProtocol = _toolbox->mavlinkProtocol(); - QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); qmlRegisterUncreatableType ("QGroundControl.MultiVehicleManager", 1, 0, "MultiVehicleManager", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "Vehicle", "Reference only"); @@ -62,7 +59,7 @@ void MultiVehicleManager::setToolbox(QGCToolbox *toolbox) qRegisterMetaType("MavCmdResultFailureCode_t"); - connect(_mavlinkProtocol, &MAVLinkProtocol::vehicleHeartbeatInfo, this, &MultiVehicleManager::_vehicleHeartbeatInfo); + connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::vehicleHeartbeatInfo, this, &MultiVehicleManager::_vehicleHeartbeatInfo); connect(&_gcsHeartbeatTimer, &QTimer::timeout, this, &MultiVehicleManager::_sendGCSHeartbeat); if (_gcsHeartbeatEnabled) { @@ -89,7 +86,7 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle // When you flash a new ArduCopter it does not set a FRAME_CLASS for some reason. This is the only ArduPilot variant which // works this way. Because of this the vehicle type is not known at first connection. In order to make QGC work reasonably // we assume ArduCopter for this case. - if (vehicleType == 0 && vehicleFirmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) { + if ((vehicleType == MAV_TYPE_GENERIC) && (vehicleFirmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA)) { vehicleType = MAV_TYPE_QUADROTOR; } #endif @@ -120,7 +117,7 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle << vehicleFirmwareType << vehicleType; - if (vehicleId == _mavlinkProtocol->getSystemId()) { + if (vehicleId == MAVLinkProtocol::instance()->getSystemId()) { _app->showAppMessage(tr("Warning: A vehicle is using the same system id as %1: %2").arg(QCoreApplication::applicationName()).arg(vehicleId)); } @@ -161,7 +158,7 @@ void MultiVehicleManager::_requestProtocolVersion(unsigned version) unsigned maxversion = 0; if (_vehicles.count() == 0) { - _mavlinkProtocol->setVersion(version); + MAVLinkProtocol::instance()->setVersion(version); return; } @@ -173,8 +170,8 @@ void MultiVehicleManager::_requestProtocolVersion(unsigned version) } } - if (_mavlinkProtocol->getCurrentVersion() != maxversion) { - _mavlinkProtocol->setVersion(maxversion); + if (MAVLinkProtocol::instance()->getCurrentVersion() != maxversion) { + MAVLinkProtocol::instance()->setVersion(maxversion); } } @@ -374,8 +371,8 @@ void MultiVehicleManager::_sendGCSHeartbeat(void) auto linkConfiguration = link->linkConfiguration(); if (link->isConnected() && linkConfiguration && !linkConfiguration->isHighLatency()) { mavlink_message_t message; - mavlink_msg_heartbeat_pack_chan(_mavlinkProtocol->getSystemId(), - _mavlinkProtocol->getComponentId(), + mavlink_msg_heartbeat_pack_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), link->mavlinkChannel(), &message, MAV_TYPE_GCS, // MAV_TYPE diff --git a/src/Vehicle/MultiVehicleManager.h b/src/Vehicle/MultiVehicleManager.h index f95a7a7a1ef..28049f6bafc 100644 --- a/src/Vehicle/MultiVehicleManager.h +++ b/src/Vehicle/MultiVehicleManager.h @@ -19,9 +19,9 @@ #include "QGCToolbox.h" #include "QmlObjectListModel.h" +#include "MAVLinkLib.h" class QGCApplication; -class MAVLinkProtocol; class LinkInterface; class Vehicle; @@ -108,7 +108,6 @@ private slots: QmlObjectListModel _vehicles; - MAVLinkProtocol* _mavlinkProtocol; QGeoCoordinate _lastKnownLocation; QTimer _gcsHeartbeatTimer; ///< Timer to emit heartbeats diff --git a/src/Vehicle/RemoteIDManager.cc b/src/Vehicle/RemoteIDManager.cc index 1ac2389ffdd..54c183a66b7 100644 --- a/src/Vehicle/RemoteIDManager.cc +++ b/src/Vehicle/RemoteIDManager.cc @@ -31,7 +31,6 @@ const uint8_t* RemoteIDManager::_id_or_mac_unknown = new uint8_t[MAVLINK_MSG_OPE RemoteIDManager::RemoteIDManager(Vehicle* vehicle) : QObject (vehicle) - , _mavlink (nullptr) , _vehicle (vehicle) , _settings (nullptr) , _armStatusGood (false) @@ -45,7 +44,6 @@ RemoteIDManager::RemoteIDManager(Vehicle* vehicle) , _targetComponent (0) // By default 0 means broadcast , _enforceSendingSelfID (false) { - _mavlink = qgcApp()->toolbox()->mavlinkProtocol(); _settings = qgcApp()->toolbox()->settingsManager()->remoteIDSettings(); // Timer to track a healthy RID device. When expired we let the operator know @@ -199,8 +197,8 @@ void RemoteIDManager::_sendSelfIDMsg() if (sharedLink) { mavlink_message_t msg; - mavlink_msg_open_drone_id_self_id_pack_chan(_mavlink->getSystemId(), - _mavlink->getComponentId(), + mavlink_msg_open_drone_id_self_id_pack_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, _targetSystem, @@ -253,8 +251,8 @@ void RemoteIDManager::_sendOperatorID() bytesOperatorID.resize(MAVLINK_MSG_OPEN_DRONE_ID_OPERATOR_ID_FIELD_OPERATOR_ID_LEN); mavlink_msg_open_drone_id_operator_id_pack_chan( - _mavlink->getSystemId(), - _mavlink->getComponentId(), + MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, _targetSystem, @@ -335,8 +333,8 @@ void RemoteIDManager::_sendSystem() if (sharedLink) { mavlink_message_t msg; - mavlink_msg_open_drone_id_system_pack_chan(_mavlink->getSystemId(), - _mavlink->getComponentId(), + mavlink_msg_open_drone_id_system_pack_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, _targetSystem, @@ -379,8 +377,8 @@ void RemoteIDManager::_sendBasicID() // To make sure the buffer is large enough to fit the message. It will add padding bytes if smaller, or exclude the extra ones if bigger ba.resize(MAVLINK_MSG_OPEN_DRONE_ID_BASIC_ID_FIELD_UAS_ID_LEN); - mavlink_msg_open_drone_id_basic_id_pack_chan(_mavlink->getSystemId(), - _mavlink->getComponentId(), + mavlink_msg_open_drone_id_basic_id_pack_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, _targetSystem, diff --git a/src/Vehicle/RemoteIDManager.h b/src/Vehicle/RemoteIDManager.h index a974d11fa63..a7641ee58a4 100644 --- a/src/Vehicle/RemoteIDManager.h +++ b/src/Vehicle/RemoteIDManager.h @@ -21,7 +21,6 @@ Q_DECLARE_LOGGING_CATEGORY(RemoteIDManagerLog) class RemoteIDSettings; class Vehicle; -class MAVLinkProtocol; // Supporting Open Drone ID protocol class RemoteIDManager : public QObject @@ -105,7 +104,6 @@ private slots: bool _isEUOperatorIDValid(const QString& operatorID) const; QChar _calculateLuhnMod36(const QString& input) const; - MAVLinkProtocol* _mavlink; Vehicle* _vehicle; RemoteIDSettings* _settings; diff --git a/src/Vehicle/TerrainProtocolHandler.cc b/src/Vehicle/TerrainProtocolHandler.cc index f77c208fe10..c54567fd7e3 100644 --- a/src/Vehicle/TerrainProtocolHandler.cc +++ b/src/Vehicle/TerrainProtocolHandler.cc @@ -164,8 +164,8 @@ void TerrainProtocolHandler::_sendTerrainData(const QGeoCoordinate &swCorner, ui if (sharedLink) { mavlink_message_t msg; (void) mavlink_msg_terrain_data_pack_chan( - qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), + MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, _currentTerrainRequest.lat, diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 875b97904f1..01a267aae87 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -116,11 +116,10 @@ Vehicle::Vehicle(LinkInterface* link, connect(JoystickManager::instance(), &JoystickManager::activeJoystickChanged, this, &Vehicle::_loadJoystickSettings); connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &Vehicle::_activeVehicleChanged); - _mavlink = _toolbox->mavlinkProtocol(); - qCDebug(VehicleLog) << "Link started with Mavlink " << (_mavlink->getCurrentVersion() >= 200 ? "V2" : "V1"); + qCDebug(VehicleLog) << "Link started with Mavlink " << (MAVLinkProtocol::instance()->getCurrentVersion() >= 200 ? "V2" : "V1"); - connect(_mavlink, &MAVLinkProtocol::messageReceived, this, &Vehicle::_mavlinkMessageReceived); - connect(_mavlink, &MAVLinkProtocol::mavlinkMessageStatus, this, &Vehicle::_mavlinkMessageStatus); + connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, &Vehicle::_mavlinkMessageReceived); + connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::mavlinkMessageStatus, this, &Vehicle::_mavlinkMessageStatus); connect(this, &Vehicle::flightModeChanged, this, &Vehicle::_handleFlightModeChanged); connect(this, &Vehicle::armedChanged, this, &Vehicle::_announceArmedChanged); @@ -364,7 +363,7 @@ void Vehicle::_commonInit() // enable Joystick if appropriate _loadJoystickSettings(); - _gimbalController = new GimbalController(_mavlink, this); + _gimbalController = new GimbalController(MAVLinkProtocol::instance(), this); } Vehicle::~Vehicle() @@ -459,7 +458,7 @@ void Vehicle::resetCounters() void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message) { // If the link is already running at Mavlink V2 set our max proto version to it. - unsigned mavlinkVersion = _mavlink->getCurrentVersion(); + unsigned mavlinkVersion = MAVLinkProtocol::instance()->getCurrentVersion(); if (_maxProtoVersion != mavlinkVersion && mavlinkVersion >= 200) { _maxProtoVersion = mavlinkVersion; qCDebug(VehicleLog) << "_mavlinkMessageReceived Link already running Mavlink v2. Setting _maxProtoVersion" << _maxProtoVersion; @@ -1135,8 +1134,8 @@ void Vehicle::_handlePing(LinkInterface* link, mavlink_message_t& message) if ((ping.target_system == 0) && (ping.target_component == 0)) { // Mavlink defines a ping request as a MSG_ID_PING which contains target_system = 0 and target_component = 0 // So only send a ping response when you receive a valid ping request - mavlink_msg_ping_pack_chan(static_cast(_mavlink->getSystemId()), - static_cast(_mavlink->getComponentId()), + mavlink_msg_ping_pack_chan(static_cast(MAVLinkProtocol::instance()->getSystemId()), + static_cast(MAVLinkProtocol::instance()->getComponentId()), sharedLink->mavlinkChannel(), &msg, ping.time_usec, @@ -1229,8 +1228,8 @@ EventHandler& Vehicle::_eventHandler(uint8_t compid) SharedLinkInterfacePtr sharedLink = vehicleLinkManager()->primaryLink().lock(); if (sharedLink) { mavlink_message_t message; - mavlink_msg_request_event_encode_chan(_mavlink->getSystemId(), - _mavlink->getComponentId(), + mavlink_msg_request_event_encode_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &message, &msg); @@ -1243,7 +1242,7 @@ EventHandler& Vehicle::_eventHandler(uint8_t compid) QSharedPointer eventHandler{new EventHandler(this, profile, std::bind(&Vehicle::_handleEvent, this, compid, std::placeholders::_1), sendRequestEventMessageCB, - _mavlink->getSystemId(), _mavlink->getComponentId(), _id, compid)}; + MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), _id, compid)}; eventData = _events.insert(compid, eventHandler); // connect health and arming check updates @@ -1657,8 +1656,8 @@ void Vehicle::setFlightMode(const QString& flightMode) custom_mode); } else { mavlink_message_t msg; - mavlink_msg_set_mode_pack_chan(_mavlink->getSystemId(), - _mavlink->getComponentId(), + mavlink_msg_set_mode_pack_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, id(), @@ -1701,8 +1700,8 @@ void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool send dataStream.target_system = id(); dataStream.target_component = _defaultComponentId; - mavlink_msg_request_data_stream_encode_chan(_mavlink->getSystemId(), - _mavlink->getComponentId(), + mavlink_msg_request_data_stream_encode_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, &dataStream); @@ -1856,8 +1855,8 @@ void Vehicle::_sendQGCTimeToVehicle() cmd.time_unix_usec = QDateTime::currentDateTime().currentMSecsSinceEpoch()*1000; // Timestamp of the component clock since boot time in milliseconds (Not necessary). cmd.time_boot_ms = 0; - mavlink_msg_system_time_encode_chan(_mavlink->getSystemId(), - _mavlink->getComponentId(), + mavlink_msg_system_time_encode_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, &cmd); @@ -2354,8 +2353,8 @@ void Vehicle::setCurrentMissionSequence(int seq) seq--; } mavlink_msg_mission_set_current_pack_chan( - static_cast(_mavlink->getSystemId()), - static_cast(_mavlink->getComponentId()), + static_cast(MAVLinkProtocol::instance()->getSystemId()), + static_cast(MAVLinkProtocol::instance()->getComponentId()), sharedLink->mavlinkChannel(), &msg, static_cast(id()), @@ -2612,8 +2611,8 @@ void Vehicle::_sendMavCommandFromList(int index) cmd.x = commandEntry.frame == MAV_FRAME_MISSION ? commandEntry.rgParam5 : commandEntry.rgParam5 * 1e7; cmd.y = commandEntry.frame == MAV_FRAME_MISSION ? commandEntry.rgParam6 : commandEntry.rgParam6 * 1e7; cmd.z = commandEntry.rgParam7; - mavlink_msg_command_int_encode_chan(_mavlink->getSystemId(), - _mavlink->getComponentId(), + mavlink_msg_command_int_encode_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, &cmd); @@ -2632,8 +2631,8 @@ void Vehicle::_sendMavCommandFromList(int index) cmd.param5 = static_cast(commandEntry.rgParam5); cmd.param6 = static_cast(commandEntry.rgParam6); cmd.param7 = commandEntry.rgParam7; - mavlink_msg_command_long_encode_chan(_mavlink->getSystemId(), - _mavlink->getComponentId(), + mavlink_msg_command_long_encode_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, &cmd); @@ -3016,8 +3015,8 @@ void Vehicle::startCalibration(QGCMAVLink::CalibrationType calType) // We can't use sendMavCommand here since we have no idea how long it will be before the command returns a result. This in turn // causes the retry logic to break down. mavlink_message_t msg; - mavlink_msg_command_long_pack_chan(_mavlink->getSystemId(), - _mavlink->getComponentId(), + mavlink_msg_command_long_pack_chan(MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, id(), @@ -3127,8 +3126,8 @@ void Vehicle::_ackMavlinkLogData(uint16_t sequence) ack.target_component = _defaultComponentId; ack.target_system = id(); mavlink_msg_logging_ack_encode_chan( - _mavlink->getSystemId(), - _mavlink->getComponentId(), + MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, &ack); @@ -3728,8 +3727,8 @@ void Vehicle::sendParamMapRC(const QString& paramName, double scale, double cent } } - mavlink_msg_param_map_rc_pack_chan(static_cast(_mavlink->getSystemId()), - static_cast(_mavlink->getComponentId()), + mavlink_msg_param_map_rc_pack_chan(static_cast(MAVLinkProtocol::instance()->getSystemId()), + static_cast(MAVLinkProtocol::instance()->getComponentId()), sharedLink->mavlinkChannel(), &message, _id, @@ -3756,8 +3755,8 @@ void Vehicle::clearAllParamMapRC(void) for (int i = 0; i < 3; i++) { mavlink_message_t message; - mavlink_msg_param_map_rc_pack_chan(static_cast(_mavlink->getSystemId()), - static_cast(_mavlink->getComponentId()), + mavlink_msg_param_map_rc_pack_chan(static_cast(MAVLinkProtocol::instance()->getSystemId()), + static_cast(MAVLinkProtocol::instance()->getComponentId()), sharedLink->mavlinkChannel(), &message, _id, @@ -3792,8 +3791,8 @@ void Vehicle::sendJoystickDataThreadSafe(float roll, float pitch, float yaw, flo float newThrustCommand = thrust * axesScaling; mavlink_msg_manual_control_pack_chan( - static_cast(_mavlink->getSystemId()), - static_cast(_mavlink->getComponentId()), + static_cast(MAVLinkProtocol::instance()->getSystemId()), + static_cast(MAVLinkProtocol::instance()->getComponentId()), sharedLink->mavlinkChannel(), &message, static_cast(_id), @@ -3856,8 +3855,8 @@ void Vehicle::setEstimatorOrigin(const QGeoCoordinate& centerCoord) mavlink_message_t msg; mavlink_msg_set_gps_global_origin_pack_chan( - _mavlink->getSystemId(), - _mavlink->getComponentId(), + MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), sharedLink->mavlinkChannel(), &msg, id(), @@ -4069,7 +4068,7 @@ void Vehicle::sendSetupSigning() MAVLinkSigning::createSetupSigning(channel, target_system, setup_signing); mavlink_message_t msg; - (void) mavlink_msg_setup_signing_encode_chan(_mavlink->getSystemId(), _mavlink->getComponentId(), channel, &msg, &setup_signing); + (void) mavlink_msg_setup_signing_encode_chan(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), channel, &msg, &setup_signing); // Since we don't get an ack back that the message was received send twice to try to make sure it makes it to the vehicle for (uint8_t i = 0; i < 2; ++i) { diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index daf6ed731e8..b0370620b36 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -60,7 +60,6 @@ class Joystick; class LinkInterface; class LinkManager; class MAVLinkLogManager; -class MAVLinkProtocol; class MissionManager; class ParameterManager; class QGCCameraManager; @@ -993,7 +992,6 @@ private slots: FirmwarePlugin* _firmwarePlugin = nullptr; QObject* _firmwarePluginInstanceData = nullptr; AutoPilotPlugin* _autopilotPlugin = nullptr; - MAVLinkProtocol* _mavlink = nullptr; bool _soloFirmware = false; QGCToolbox* _toolbox = nullptr; SettingsManager* _settingsManager = nullptr; diff --git a/test/AnalyzeView/MavlinkLogTest.cc b/test/AnalyzeView/MavlinkLogTest.cc index 2328e2a9129..d5291e02a58 100644 --- a/test/AnalyzeView/MavlinkLogTest.cc +++ b/test/AnalyzeView/MavlinkLogTest.cc @@ -78,7 +78,7 @@ void MavlinkLogTest::_bootLogDetectionCancel_test(void) setExpectedFileDialog(getSaveFileName, QStringList()); // Kick the protocol to check for lost log files and wait for signals to move through - connect(this, &MavlinkLogTest::checkForLostLogFiles, qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::checkForLostLogFiles); + connect(this, &MavlinkLogTest::checkForLostLogFiles, MAVLinkProtocol::instance(), &MAVLinkProtocol::checkForLostLogFiles); emit checkForLostLogFiles(); QTest::qWait(1000); @@ -98,7 +98,7 @@ void MavlinkLogTest::_bootLogDetectionSave_test(void) setExpectedFileDialog(getSaveFileName, QStringList(logSaveFile)); // Kick the protocol to check for lost log files and wait for signals to move through - connect(this, &MavlinkLogTest::checkForLostLogFiles, qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::checkForLostLogFiles); + connect(this, &MavlinkLogTest::checkForLostLogFiles, MAVLinkProtocol::instance(), &MAVLinkProtocol::checkForLostLogFiles); emit checkForLostLogFiles(); QTest::qWait(1000); @@ -115,7 +115,7 @@ void MavlinkLogTest::_bootLogDetectionZeroLength_test(void) _createTempLogFile(true); // Kick the protocol to check for lost log files and wait for signals to move through - connect(this, &MavlinkLogTest::checkForLostLogFiles, qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::checkForLostLogFiles); + connect(this, &MavlinkLogTest::checkForLostLogFiles, MAVLinkProtocol::instance(), &MAVLinkProtocol::checkForLostLogFiles); emit checkForLostLogFiles(); QTest::qWait(1000);