diff --git a/src/AnalyzeView/LogDownloadController.cc b/src/AnalyzeView/LogDownloadController.cc index a9c8f676489..a100b86c071 100644 --- a/src/AnalyzeView/LogDownloadController.cc +++ b/src/AnalyzeView/LogDownloadController.cc @@ -34,10 +34,9 @@ LogDownloadController::LogDownloadController(void) , _retries(0) , _apmOneBased(0) { - MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager(); - connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &LogDownloadController::_setActiveVehicle); + connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &LogDownloadController::_setActiveVehicle); connect(&_timer, &QTimer::timeout, this, &LogDownloadController::_processDownload); - _setActiveVehicle(manager->activeVehicle()); + _setActiveVehicle(MultiVehicleManager::instance()->activeVehicle()); } //---------------------------------------------------------------------------------------- @@ -600,7 +599,7 @@ LogDownloadController::eraseAll(void) MAVLinkProtocol::getComponentId(), sharedLink->mavlinkChannel(), &msg, - qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->defaultComponentId()); + MultiVehicleManager::instance()->activeVehicle()->id(), MultiVehicleManager::instance()->activeVehicle()->defaultComponentId()); _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg); } refresh(); diff --git a/src/AnalyzeView/MAVLinkConsoleController.cc b/src/AnalyzeView/MAVLinkConsoleController.cc index 9ff972f58da..fc1695d078c 100644 --- a/src/AnalyzeView/MAVLinkConsoleController.cc +++ b/src/AnalyzeView/MAVLinkConsoleController.cc @@ -27,10 +27,9 @@ MAVLinkConsoleController::MAVLinkConsoleController(QObject *parent) { // qCDebug(MAVLinkConsoleControllerLog) << Q_FUNC_INFO << this; - MultiVehicleManager *const manager = qgcApp()->toolbox()->multiVehicleManager(); - (void) connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkConsoleController::_setActiveVehicle); + (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkConsoleController::_setActiveVehicle); - _setActiveVehicle(manager->activeVehicle()); + _setActiveVehicle(MultiVehicleManager::instance()->activeVehicle()); } MAVLinkConsoleController::~MAVLinkConsoleController() diff --git a/src/AnalyzeView/MAVLinkInspectorController.cc b/src/AnalyzeView/MAVLinkInspectorController.cc index 9fb2e66f6d2..81737981db6 100644 --- a/src/AnalyzeView/MAVLinkInspectorController.cc +++ b/src/AnalyzeView/MAVLinkInspectorController.cc @@ -24,10 +24,9 @@ QGC_LOGGING_CATEGORY(MAVLinkInspectorControllerLog, "qgc.analyzeview.mavlinkinsp //----------------------------------------------------------------------------- MAVLinkInspectorController::MAVLinkInspectorController() { - MultiVehicleManager* multiVehicleManager = qgcApp()->toolbox()->multiVehicleManager(); - connect(multiVehicleManager, &MultiVehicleManager::vehicleAdded, this, &MAVLinkInspectorController::_vehicleAdded); - connect(multiVehicleManager, &MultiVehicleManager::vehicleRemoved, this, &MAVLinkInspectorController::_vehicleRemoved); - connect(multiVehicleManager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkInspectorController::_setActiveVehicle); + connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleAdded, this, &MAVLinkInspectorController::_vehicleAdded); + connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleRemoved, this, &MAVLinkInspectorController::_vehicleRemoved); + connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkInspectorController::_setActiveVehicle); connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, &MAVLinkInspectorController::_receiveMessage); connect(&_updateFrequencyTimer, &QTimer::timeout, this, &MAVLinkInspectorController::_refreshFrequency); _updateFrequencyTimer.start(1000); @@ -256,13 +255,10 @@ void MAVLinkInspectorController::setMessageInterval(int32_t rate) { if(!_activeSystem) return; - MultiVehicleManager* multiVehicleManager = qgcApp()->toolbox()->multiVehicleManager(); - if(!multiVehicleManager) return; - const uint8_t sysId = _selectedSystemID(); if(sysId == 0) return; - Vehicle* vehicle = multiVehicleManager->getVehicleById(sysId); + Vehicle* vehicle = MultiVehicleManager::instance()->getVehicleById(sysId); if(!vehicle) return; QGCMAVLinkMessage* msg = _activeSystem->selectedMsg(); diff --git a/src/AutoPilotPlugins/PX4/AirframeComponentController.cc b/src/AutoPilotPlugins/PX4/AirframeComponentController.cc index ea0344557c5..6ed4039f5e2 100644 --- a/src/AutoPilotPlugins/PX4/AirframeComponentController.cc +++ b/src/AutoPilotPlugins/PX4/AirframeComponentController.cc @@ -85,7 +85,7 @@ AirframeComponentController::~AirframeComponentController() void AirframeComponentController::changeAutostart(void) { - if (qgcApp()->toolbox()->multiVehicleManager()->vehicles()->count() > 1) { + if (MultiVehicleManager::instance()->vehicles()->count() > 1) { qgcApp()->showAppMessage(tr("You cannot change airframe configuration while connected to multiple vehicles.")); return; } diff --git a/src/Camera/QGCCameraManager.cc b/src/Camera/QGCCameraManager.cc index db5e9f8ce56..3a79d22bbcc 100644 --- a/src/Camera/QGCCameraManager.cc +++ b/src/Camera/QGCCameraManager.cc @@ -50,7 +50,7 @@ QGCCameraManager::QGCCameraManager(Vehicle *vehicle) _addCameraControlToLists(_simulatedCameraControl); - connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &QGCCameraManager::_vehicleReady); + connect(MultiVehicleManager::instance(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &QGCCameraManager::_vehicleReady); connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &QGCCameraManager::_mavlinkMessageReceived); connect(&_camerasLostHeartbeatTimer, &QTimer::timeout, this, &QGCCameraManager::_checkForLostCameras); @@ -87,7 +87,7 @@ void QGCCameraManager::_vehicleReady(bool ready) { qCDebug(CameraManagerLog) << "_vehicleReady(" << ready << ")"; if(ready) { - if(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle() == _vehicle) { + if(MultiVehicleManager::instance()->activeVehicle() == _vehicle) { _vehicleReadyState = true; _activeJoystickChanged(JoystickManager::instance()->activeJoystick()); connect(JoystickManager::instance(), &JoystickManager::activeJoystickChanged, this, &QGCCameraManager::_activeJoystickChanged); diff --git a/src/Comms/LinkManager.cc b/src/Comms/LinkManager.cc index fa38bff10b4..7f3b191f9b6 100644 --- a/src/Comms/LinkManager.cc +++ b/src/Comms/LinkManager.cc @@ -237,8 +237,6 @@ void LinkManager::_linkDisconnected() for (auto it = _rgLinks.begin(); it != _rgLinks.end(); ++it) { if (it->get() == link) { qCDebug(LinkManagerLog) << Q_FUNC_INFO << it->get()->linkConfiguration()->name() << it->use_count(); - SharedLinkConfigurationPtr config = it->get()->linkConfiguration(); - config->setLink(nullptr); (void) _rgLinks.erase(it); return; } @@ -511,7 +509,7 @@ void LinkManager::shutdown() disconnectAll(); // Wait for all the vehicles to go away to ensure an orderly shutdown and deletion of all objects - while (qgcApp()->toolbox()->multiVehicleManager()->vehicles()->count()) { + while (MultiVehicleManager::instance()->vehicles()->count()) { QCoreApplication::processEvents(QEventLoop::ExcludeUserInputEvents); } } diff --git a/src/Comms/LogReplayLink.cc b/src/Comms/LogReplayLink.cc index c3bd3f6aaef..4ce220caabb 100644 --- a/src/Comms/LogReplayLink.cc +++ b/src/Comms/LogReplayLink.cc @@ -103,7 +103,7 @@ LogReplayLink::~LogReplayLink(void) bool LogReplayLink::_connect(void) { // Disallow replay when any links are connected - if (qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()) { + if (MultiVehicleManager::instance()->activeVehicle()) { emit communicationError(_errorTitle, tr("You must close all connections prior to replaying a log.")); return false; } diff --git a/src/Comms/MAVLinkProtocol.cc b/src/Comms/MAVLinkProtocol.cc index 01035056f69..092b8a60350 100644 --- a/src/Comms/MAVLinkProtocol.cc +++ b/src/Comms/MAVLinkProtocol.cc @@ -15,6 +15,7 @@ #include "QGCTemporaryFile.h" #include "QGCToolbox.h" #include "SettingsManager.h" +#include "QmlObjectListModel.h" #include #include @@ -25,19 +26,13 @@ QGC_LOGGING_CATEGORY(MAVLinkProtocolLog, "qgc.comms.mavlinkprotocol") -Q_APPLICATION_STATIC(MAVLinkProtocol, _mavlinkProtocol); +Q_APPLICATION_STATIC(MAVLinkProtocol, _mavlinkProtocolInstance); MAVLinkProtocol::MAVLinkProtocol(QObject *parent) : QObject(parent) , _tempLogFile(new QGCTemporaryFile(QStringLiteral("%2.%3").arg(_tempLogFileTemplate, _logFileExtension), this)) { // qCDebug(MAVLinkProtocolLog) << Q_FUNC_INFO << this; - - (void) memset(_firstMessage, 1, sizeof(_firstMessage)); - - (void) connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleRemoved, this, &MAVLinkProtocol::_vehicleCountChanged); - - _loadSettings(); } MAVLinkProtocol::~MAVLinkProtocol() @@ -50,7 +45,22 @@ MAVLinkProtocol::~MAVLinkProtocol() MAVLinkProtocol *MAVLinkProtocol::instance() { - return _mavlinkProtocol(); + return _mavlinkProtocolInstance(); +} + +void MAVLinkProtocol::init() +{ + if (_initialized) { + return; + } + + (void) memset(_firstMessage, 1, sizeof(_firstMessage)); + + (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleRemoved, this, &MAVLinkProtocol::_vehicleCountChanged); + + _loadSettings(); + + _initialized = true; } void MAVLinkProtocol::setVersion(unsigned version) @@ -476,7 +486,7 @@ void MAVLinkProtocol::enableVersionCheck(bool enabled) void MAVLinkProtocol::_vehicleCountChanged() { - if (qgcApp()->toolbox()->multiVehicleManager()->vehicles()->count() == 0) { + if (MultiVehicleManager::instance()->vehicles()->count() == 0) { _stopLogging(); } } diff --git a/src/Comms/MAVLinkProtocol.h b/src/Comms/MAVLinkProtocol.h index 2a603f816f8..a8ffe5cdce3 100644 --- a/src/Comms/MAVLinkProtocol.h +++ b/src/Comms/MAVLinkProtocol.h @@ -40,6 +40,8 @@ class MAVLinkProtocol : public QObject /// @return The singleton instance. static MAVLinkProtocol *instance(); + void init(); + /// Get the human-friendly name of this protocol static QString getName() { return QStringLiteral("MAVLink protocol"); } @@ -143,6 +145,7 @@ private slots: int _systemId = kMaxSysId; unsigned _currentVersion = 100; + bool _initialized = false; 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/FactSystem/FactControls/FactPanelController.cc b/src/FactSystem/FactControls/FactPanelController.cc index 14a83fd2d79..cc8760f6f0a 100644 --- a/src/FactSystem/FactControls/FactPanelController.cc +++ b/src/FactSystem/FactControls/FactPanelController.cc @@ -25,11 +25,11 @@ QGC_LOGGING_CATEGORY(FactPanelControllerLog, "FactPanelControllerLog") FactPanelController::FactPanelController(QObject *parent) : QObject(parent) { - _vehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle(); + _vehicle = MultiVehicleManager::instance()->activeVehicle(); if (_vehicle) { _autopilot = _vehicle->autopilotPlugin(); } else { - _vehicle = qgcApp()->toolbox()->multiVehicleManager()->offlineEditingVehicle(); + _vehicle = MultiVehicleManager::instance()->offlineEditingVehicle(); } _missingParametersTimer.setInterval(500); diff --git a/src/FollowMe/FollowMe.cc b/src/FollowMe/FollowMe.cc index 8995384fd3a..1e69be7ea68 100644 --- a/src/FollowMe/FollowMe.cc +++ b/src/FollowMe/FollowMe.cc @@ -60,18 +60,18 @@ void FollowMe::_settingsChanged(QVariant value) switch (_currentMode) { case MODE_NEVER: - (void) disconnect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded); - (void) disconnect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved); + (void) disconnect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded); + (void) disconnect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved); _disableFollowSend(); break; case MODE_ALWAYS: - (void) connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded); - (void) connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved); + (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded); + (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved); _enableFollowSend(); break; case MODE_FOLLOWME: - (void) connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded); - (void) connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved); + (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded); + (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved); _enableIfVehicleInFollow(); break; } @@ -106,7 +106,7 @@ void FollowMe::_sendGCSMotionReport() if (_currentMode == MODE_ALWAYS) { needFollowMe = true; } else if (_currentMode == MODE_FOLLOWME) { - QmlObjectListModel* const vehicles = qgcApp()->toolbox()->multiVehicleManager()->vehicles(); + QmlObjectListModel* const vehicles = MultiVehicleManager::instance()->vehicles(); for (int i = 0; i < vehicles->count(); i++) { const Vehicle* const vehicle = vehicles->value(i); if (_isFollowFlightMode(vehicle, vehicle->flightMode())) { @@ -162,7 +162,7 @@ void FollowMe::_sendGCSMotionReport() motionReport.vyMetersPerSec = 0; } - QmlObjectListModel* const vehicles = qgcApp()->toolbox()->multiVehicleManager()->vehicles(); + QmlObjectListModel* const vehicles = MultiVehicleManager::instance()->vehicles(); for (int i = 0; i < vehicles->count(); i++) { Vehicle* const vehicle = vehicles->value(i); @@ -192,7 +192,7 @@ void FollowMe::_enableIfVehicleInFollow() } // Any vehicle in follow mode will enable the system - QmlObjectListModel* const vehicles = qgcApp()->toolbox()->multiVehicleManager()->vehicles(); + QmlObjectListModel* const vehicles = MultiVehicleManager::instance()->vehicles(); for (int i = 0; i < vehicles->count(); i++) { const Vehicle* const vehicle = vehicles->value(i); diff --git a/src/GPS/RTCMMavlink.cc b/src/GPS/RTCMMavlink.cc index 3b7d7b7a406..e73d8de1153 100644 --- a/src/GPS/RTCMMavlink.cc +++ b/src/GPS/RTCMMavlink.cc @@ -66,7 +66,7 @@ void RTCMMavlink::RTCMDataUpdate(QByteArrayView data) void RTCMMavlink::_sendMessageToVehicle(const mavlink_gps_rtcm_data_t &data) { - QmlObjectListModel* const vehicles = qgcApp()->toolbox()->multiVehicleManager()->vehicles(); + QmlObjectListModel* const vehicles = MultiVehicleManager::instance()->vehicles(); for (qsizetype i = 0; i < vehicles->count(); i++) { Vehicle* const vehicle = qobject_cast(vehicles->get(i)); const SharedLinkInterfacePtr sharedLink = vehicle->vehicleLinkManager()->primaryLink().lock(); diff --git a/src/Joystick/Joystick.cc b/src/Joystick/Joystick.cc index c44274119e5..7908e3b5687 100644 --- a/src/Joystick/Joystick.cc +++ b/src/Joystick/Joystick.cc @@ -41,14 +41,13 @@ AssignableButtonAction::AssignableButtonAction(QObject* parent, QString action_, { } -Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatCount, MultiVehicleManager* multiVehicleManager) +Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatCount) : _name (name) , _axisCount (axisCount) , _buttonCount (buttonCount) , _hatCount (hatCount) , _hatButtonCount (4 * hatCount) , _totalButtonCount (_buttonCount+_hatButtonCount) - , _multiVehicleManager (multiVehicleManager) , _customActionManager (qgcApp()->toolbox()->settingsManager()->customMavlinkActionsSettings()->joystickActionsFile()) { // qCDebug(JoystickLog) << Q_FUNC_INFO << this; @@ -65,11 +64,11 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC _rgButtonValues[i] = BUTTON_UP; _buttonActionArray.append(nullptr); } - _buildActionList(_multiVehicleManager->activeVehicle()); - _updateTXModeSettingsKey(_multiVehicleManager->activeVehicle()); + _buildActionList(MultiVehicleManager::instance()->activeVehicle()); + _updateTXModeSettingsKey(MultiVehicleManager::instance()->activeVehicle()); _loadSettings(); - connect(_multiVehicleManager, &MultiVehicleManager::activeVehicleChanged, this, &Joystick::_activeVehicleChanged); - connect(qgcApp()->toolbox()->multiVehicleManager()->vehicles(), &QmlObjectListModel::countChanged, this, &Joystick::_vehicleCountChanged); + connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &Joystick::_activeVehicleChanged); + connect(MultiVehicleManager::instance()->vehicles(), &QmlObjectListModel::countChanged, this, &Joystick::_vehicleCountChanged); } void Joystick::stop() @@ -186,7 +185,7 @@ void Joystick::_loadSettings() { QSettings settings; settings.beginGroup(_settingsGroup); - Vehicle* activeVehicle = _multiVehicleManager->activeVehicle(); + Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle(); if(_txModeSettingsKey && activeVehicle) _transmitterMode = settings.value(_txModeSettingsKey, activeVehicle->firmwarePlugin()->defaultJoystickTXMode()).toInt(); @@ -953,7 +952,7 @@ void Joystick::setCalibrationMode(bool calibrating) _calibrationMode = calibrating; if (calibrating && !isRunning()) { _pollingStartedForCalibration = true; - startPolling(_multiVehicleManager->activeVehicle()); + startPolling(MultiVehicleManager::instance()->activeVehicle()); } else if (_pollingStartedForCalibration) { stopPolling(); diff --git a/src/Joystick/Joystick.h b/src/Joystick/Joystick.h index 0592c35a269..1835cd00f4c 100644 --- a/src/Joystick/Joystick.h +++ b/src/Joystick/Joystick.h @@ -26,7 +26,6 @@ Q_DECLARE_LOGGING_CATEGORY(JoystickValuesLog) Q_DECLARE_METATYPE(GRIPPER_ACTIONS) -class MultiVehicleManager; class Vehicle; class QmlObjectListModel; @@ -63,7 +62,7 @@ class Joystick : public QThread Q_MOC_INCLUDE("QmlObjectListModel.h") Q_MOC_INCLUDE("Vehicle.h") public: - Joystick(const QString& name, int axisCount, int buttonCount, int hatCount, MultiVehicleManager* multiVehicleManager); + Joystick(const QString& name, int axisCount, int buttonCount, int hatCount); virtual ~Joystick(); @@ -307,7 +306,6 @@ class Joystick : public QThread QmlObjectListModel _assignableButtonActions; QList _buttonActionArray; QStringList _availableActionTitles; - MultiVehicleManager* _multiVehicleManager = nullptr; CustomActionManager _customActionManager; diff --git a/src/Joystick/JoystickAndroid.cc b/src/Joystick/JoystickAndroid.cc index 0bbf431ea7c..539c90006d6 100644 --- a/src/Joystick/JoystickAndroid.cc +++ b/src/Joystick/JoystickAndroid.cc @@ -9,7 +9,6 @@ #include "JoystickAndroid.h" #include "JoystickManager.h" -#include "MultiVehicleManager.h" #include "QGCLoggingCategory.h" #include @@ -32,8 +31,8 @@ static void clear_jni_exception() } } -JoystickAndroid::JoystickAndroid(const QString& name, int axisCount, int buttonCount, int id, MultiVehicleManager* multiVehicleManager) - : Joystick(name,axisCount,buttonCount,0,multiVehicleManager) +JoystickAndroid::JoystickAndroid(const QString& name, int axisCount, int buttonCount, int id) + : Joystick(name,axisCount,buttonCount,0) , deviceId(id) { int i; @@ -95,7 +94,7 @@ JoystickAndroid::~JoystickAndroid() { } -QMap JoystickAndroid::discover(MultiVehicleManager* _multiVehicleManager) { +QMap JoystickAndroid::discover() { static QMap ret; QMutexLocker lock(&m_mutex); @@ -144,7 +143,7 @@ QMap JoystickAndroid::discover(MultiVehicleManager* _multiVe qCDebug(JoystickLog) << "\t" << name << "id:" << buff[i] << "axes:" << axisCount << "buttons:" << buttonCount; - ret[name] = new JoystickAndroid(name, axisCount, buttonCount, buff[i], _multiVehicleManager); + ret[name] = new JoystickAndroid(name, axisCount, buttonCount, buff[i]); } for (auto i = ret.begin(); i != ret.end();) { diff --git a/src/Joystick/JoystickAndroid.h b/src/Joystick/JoystickAndroid.h index bf96ebebc1d..2d5ab491c89 100644 --- a/src/Joystick/JoystickAndroid.h +++ b/src/Joystick/JoystickAndroid.h @@ -12,19 +12,17 @@ #include "Joystick.h" #include -class MultiVehicleManager; - class JoystickAndroid : public Joystick, public QtAndroidPrivate::GenericMotionEventListener, public QtAndroidPrivate::KeyEventListener { public: - JoystickAndroid(const QString& name, int axisCount, int buttonCount, int id, MultiVehicleManager* multiVehicleManager); + JoystickAndroid(const QString& name, int axisCount, int buttonCount, int id); ~JoystickAndroid(); static bool init(); static void setNativeMethods(); - static QMap discover(MultiVehicleManager* _multiVehicleManager); + static QMap discover(); private: bool handleKeyEvent(jobject event); diff --git a/src/Joystick/JoystickManager.cc b/src/Joystick/JoystickManager.cc index f2562540369..5fcf800f77d 100644 --- a/src/Joystick/JoystickManager.cc +++ b/src/Joystick/JoystickManager.cc @@ -80,9 +80,9 @@ void JoystickManager::_setActiveJoystickFromSettings() QMap newMap; #ifdef QGC_SDL_JOYSTICK - newMap = JoystickSDL::discover(qgcApp()->toolbox()->multiVehicleManager()); + newMap = JoystickSDL::discover(); #elif defined(Q_OS_ANDROID) - newMap = JoystickAndroid::discover(qgcApp()->toolbox()->multiVehicleManager()); + newMap = JoystickAndroid::discover(); #endif if (_activeJoystick && !newMap.contains(_activeJoystick->name())) { diff --git a/src/Joystick/JoystickSDL.cc b/src/Joystick/JoystickSDL.cc index 92d27b6f2f4..8c2632a7517 100644 --- a/src/Joystick/JoystickSDL.cc +++ b/src/Joystick/JoystickSDL.cc @@ -15,8 +15,8 @@ #include #include -JoystickSDL::JoystickSDL(const QString& name, int axisCount, int buttonCount, int hatCount, int index, bool isGameController, MultiVehicleManager* multiVehicleManager) - : Joystick(name,axisCount,buttonCount,hatCount,multiVehicleManager) +JoystickSDL::JoystickSDL(const QString& name, int axisCount, int buttonCount, int hatCount, int index, bool isGameController) + : Joystick(name,axisCount,buttonCount,hatCount) , _isGameController(isGameController) , _index(index) { @@ -41,7 +41,7 @@ bool JoystickSDL::init(void) { return true; } -QMap JoystickSDL::discover(MultiVehicleManager* _multiVehicleManager) { +QMap JoystickSDL::discover() { static QMap ret; QMap newRet; @@ -83,7 +83,7 @@ QMap JoystickSDL::discover(MultiVehicleManager* _multiVehicl name = QString("%1 %2").arg(originalName).arg(duplicateIdx++); } - newRet[name] = new JoystickSDL(name, qMax(0,axisCount), qMax(0,buttonCount), qMax(0,hatCount), i, isGameController, _multiVehicleManager); + newRet[name] = new JoystickSDL(name, qMax(0,axisCount), qMax(0,buttonCount), qMax(0,hatCount), i, isGameController); } else { newRet[name] = ret[name]; JoystickSDL *j = static_cast(newRet[name]); diff --git a/src/Joystick/JoystickSDL.h b/src/Joystick/JoystickSDL.h index 6cf81c28454..de400a615bb 100644 --- a/src/Joystick/JoystickSDL.h +++ b/src/Joystick/JoystickSDL.h @@ -24,10 +24,10 @@ class MultiVehicleManager; class JoystickSDL : public Joystick { public: - JoystickSDL(const QString& name, int axisCount, int buttonCount, int hatCount, int index, bool isGameController, MultiVehicleManager* multiVehicleManager); + JoystickSDL(const QString& name, int axisCount, int buttonCount, int hatCount, int index, bool isGameController); ~JoystickSDL(); - static QMap discover(MultiVehicleManager* _multiVehicleManager); + static QMap discover(); static bool init(void); int index(void) const { return _index; } diff --git a/src/MissionManager/PlanMasterController.cc b/src/MissionManager/PlanMasterController.cc index 91133889fd2..523125d4723 100644 --- a/src/MissionManager/PlanMasterController.cc +++ b/src/MissionManager/PlanMasterController.cc @@ -33,7 +33,7 @@ QGC_LOGGING_CATEGORY(PlanMasterControllerLog, "PlanMasterControllerLog") PlanMasterController::PlanMasterController(QObject* parent) : QObject (parent) - , _multiVehicleMgr (qgcApp()->toolbox()->multiVehicleManager()) + , _multiVehicleMgr (MultiVehicleManager::instance()) , _controllerVehicle (new Vehicle(Vehicle::MAV_AUTOPILOT_TRACK, Vehicle::MAV_TYPE_TRACK, this)) , _managerVehicle (_controllerVehicle) , _missionController (this) @@ -46,7 +46,7 @@ PlanMasterController::PlanMasterController(QObject* parent) #ifdef QT_DEBUG PlanMasterController::PlanMasterController(MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, QObject* parent) : QObject (parent) - , _multiVehicleMgr (qgcApp()->toolbox()->multiVehicleManager()) + , _multiVehicleMgr (MultiVehicleManager::instance()) , _controllerVehicle (new Vehicle(firmwareType, vehicleType)) , _managerVehicle (_controllerVehicle) , _missionController (this) diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc index f754c891676..3ca110fa9c0 100644 --- a/src/MissionManager/SimpleMissionItem.cc +++ b/src/MissionManager/SimpleMissionItem.cc @@ -496,7 +496,7 @@ void SimpleMissionItem::_rebuildNaNFacts(void) if (showUI && paramInfo && paramInfo->nanUnchanged()) { // Show hide Heading field on waypoint based on vehicle yaw to next waypoint setting. This needs to come from the actual vehicle if it exists // and not _controllerVehicle which is always offline. - Vehicle* firmwareVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle(); + Vehicle* firmwareVehicle = MultiVehicleManager::instance()->activeVehicle(); if (!firmwareVehicle) { firmwareVehicle = _controllerVehicle; } diff --git a/src/MissionManager/TakeoffMissionItem.cc b/src/MissionManager/TakeoffMissionItem.cc index 769d502ea68..314b5088194 100644 --- a/src/MissionManager/TakeoffMissionItem.cc +++ b/src/MissionManager/TakeoffMissionItem.cc @@ -57,7 +57,7 @@ void TakeoffMissionItem::_init(bool forLoad) QGeoCoordinate homePosition = _settingsItem->coordinate(); if (!homePosition.isValid()) { - Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle(); + Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle(); if (activeVehicle) { homePosition = activeVehicle->homePosition(); if (homePosition.isValid()) { diff --git a/src/PositionManager/PositionManager.cpp b/src/PositionManager/PositionManager.cpp index 8407e2bac27..ed80dbb4e44 100644 --- a/src/PositionManager/PositionManager.cpp +++ b/src/PositionManager/PositionManager.cpp @@ -29,8 +29,6 @@ QGCPositionManager::QGCPositionManager(QObject *parent) : QObject(parent) { // qCDebug(QGCPositionManagerLog) << Q_FUNC_INFO << this; - - (void) qmlRegisterUncreatableType("QGroundControl.QGCPositionManager", 1, 0, "QGCPositionManager", "Reference only"); } QGCPositionManager::~QGCPositionManager() @@ -43,6 +41,11 @@ QGCPositionManager *QGCPositionManager::instance() return _positionManager(); } +void QGCPositionManager::registerQmlTypes() +{ + (void) qmlRegisterUncreatableType("QGroundControl.QGCPositionManager", 1, 0, "QGCPositionManager", "Reference only"); +} + void QGCPositionManager::init() { if (qgcApp()->runningUnitTests()) { diff --git a/src/PositionManager/PositionManager.h b/src/PositionManager/PositionManager.h index 8627116cf25..c30f58ed015 100644 --- a/src/PositionManager/PositionManager.h +++ b/src/PositionManager/PositionManager.h @@ -38,14 +38,7 @@ class QGCPositionManager : public QObject /// Gets the singleton instance of AudioOutput. /// @return The singleton instance. static QGCPositionManager *instance(); - - enum QGCPositionSource { - Simulated, - InternalGPS, - Log, - NmeaGPS, - ExternalGPS - }; + static void registerQmlTypes(); void init(); QGeoCoordinate gcsPosition() const { return _gcsPosition; } @@ -66,6 +59,14 @@ private slots: void _positionUpdated(const QGeoPositionInfo &update); private: + enum QGCPositionSource { + Simulated, + InternalGPS, + Log, + NmeaGPS, + ExternalGPS + }; + void _setPositionSource(QGCPositionSource source); void _setupPositionSources(); void _handlePermissionStatus(Qt::PermissionStatus permissionStatus); diff --git a/src/PositionManager/SimulatedPosition.cc b/src/PositionManager/SimulatedPosition.cc index 19cb4c880f5..721f2d2aadd 100644 --- a/src/PositionManager/SimulatedPosition.cc +++ b/src/PositionManager/SimulatedPosition.cc @@ -30,7 +30,7 @@ SimulatedPosition::SimulatedPosition(QObject* parent) _lastPosition.setAttribute(QGeoPositionInfo::Attribute::GroundSpeed, kHorizontalVelocityMetersPerSec); _lastPosition.setAttribute(QGeoPositionInfo::Attribute::VerticalSpeed, kVerticalVelocityMetersPerSec); - (void) connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleAdded, this, &SimulatedPosition::_vehicleAdded); + (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleAdded, this, &SimulatedPosition::_vehicleAdded); _updateTimer->setSingleShot(false); (void) connect(_updateTimer, &QTimer::timeout, this, &SimulatedPosition::_updatePosition); diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 511e0f8a133..b5d5477c399 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -46,6 +46,7 @@ #include "MAVLinkConsoleController.h" #include "MAVLinkProtocol.h" #include "MissionManager.h" +#include "MultiVehicleManager.h" #include "ParameterManager.h" #include "PositionManager.h" #include "QGCCameraManager.h" @@ -270,6 +271,8 @@ void QGCApplication::init() QGroundControlQmlGlobal::registerQmlTypes(); MissionManager::registerQmlTypes(); QGCCameraManager::registerQmlTypes(); + MultiVehicleManager::registerQmlTypes(); + QGCPositionManager::registerQmlTypes(); #ifdef QGC_VIEWER3D Viewer3DManager::registerQmlTypes(); #endif @@ -335,6 +338,8 @@ void QGCApplication::_initForNormalAppBoot() FollowMe::instance()->init(); QGCPositionManager::instance()->init(); LinkManager::instance()->init(); + MultiVehicleManager::instance()->init(); + MAVLinkProtocol::instance()->init(); // Image provider for Optical Flow _qmlAppEngine->addImageProvider(qgcImageProviderId, new QGCImageProvider()); diff --git a/src/QGCToolbox.cc b/src/QGCToolbox.cc index 5030722c271..e89da6784dc 100644 --- a/src/QGCToolbox.cc +++ b/src/QGCToolbox.cc @@ -8,7 +8,6 @@ ****************************************************************************/ #include "QGCToolbox.h" -#include "MultiVehicleManager.h" #include "QGCCorePlugin.h" #include "SettingsManager.h" #include "QGCApplication.h" @@ -25,7 +24,6 @@ QGCToolbox::QGCToolbox(QGCApplication* app) //-- Scan and load plugins _scanAndLoadPlugins(app); - _multiVehicleManager = new MultiVehicleManager (app, this); } void QGCToolbox::setChildToolboxes(void) @@ -34,7 +32,6 @@ void QGCToolbox::setChildToolboxes(void) _settingsManager->setToolbox(this); _corePlugin->setToolbox(this); - _multiVehicleManager->setToolbox(this); } void QGCToolbox::_scanAndLoadPlugins(QGCApplication* app) diff --git a/src/QGCToolbox.h b/src/QGCToolbox.h index fa37268cb20..e13cdc37a8a 100644 --- a/src/QGCToolbox.h +++ b/src/QGCToolbox.h @@ -13,7 +13,6 @@ #include -class MultiVehicleManager; class QGCApplication; class QGCCorePlugin; class SettingsManager; @@ -25,7 +24,6 @@ class QGCToolbox : public QObject { public: QGCToolbox(QGCApplication* app); - MultiVehicleManager* multiVehicleManager () { return _multiVehicleManager; } QGCCorePlugin* corePlugin () { return _corePlugin; } SettingsManager* settingsManager () { return _settingsManager; } @@ -33,7 +31,6 @@ class QGCToolbox : public QObject { void setChildToolboxes(void); void _scanAndLoadPlugins(QGCApplication *app); - MultiVehicleManager* _multiVehicleManager = nullptr; QGCCorePlugin* _corePlugin = nullptr; SettingsManager* _settingsManager = nullptr; friend class QGCApplication; diff --git a/src/QmlControls/EditPositionDialogController.cc b/src/QmlControls/EditPositionDialogController.cc index 245581bd378..3d862cfe4a7 100644 --- a/src/QmlControls/EditPositionDialogController.cc +++ b/src/QmlControls/EditPositionDialogController.cc @@ -106,6 +106,6 @@ void EditPositionDialogController::setFromMGRS() void EditPositionDialogController::setFromVehicle() { - setCoordinate(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->coordinate()); + setCoordinate(MultiVehicleManager::instance()->activeVehicle()->coordinate()); } diff --git a/src/QmlControls/FactValueGrid.cc b/src/QmlControls/FactValueGrid.cc index 2298680bdbf..4d4b0363404 100644 --- a/src/QmlControls/FactValueGrid.cc +++ b/src/QmlControls/FactValueGrid.cc @@ -49,7 +49,7 @@ FactValueGrid::FactValueGrid(const QString& defaultSettingsGroup) void FactValueGrid::_init(void) { - Vehicle* offlineVehicle = qgcApp()->toolbox()->multiVehicleManager()->offlineEditingVehicle(); + Vehicle* offlineVehicle = MultiVehicleManager::instance()->offlineEditingVehicle(); connect(offlineVehicle, &Vehicle::vehicleTypeChanged, this, &FactValueGrid::_offlineVehicleTypeChanged); connect(this, &FactValueGrid::fontSizeChanged, this, &FactValueGrid::_saveSettings); @@ -59,7 +59,7 @@ void FactValueGrid::_init(void) void FactValueGrid::_offlineVehicleTypeChanged(void) { - Vehicle* offlineVehicle = qgcApp()->toolbox()->multiVehicleManager()->offlineEditingVehicle(); + Vehicle* offlineVehicle = MultiVehicleManager::instance()->offlineEditingVehicle(); QGCMAVLink::VehicleClass_t newVehicleClass = QGCMAVLink::vehicleClass(offlineVehicle->vehicleType()); if (newVehicleClass != _vehicleClass) { diff --git a/src/QmlControls/InstrumentValueData.cc b/src/QmlControls/InstrumentValueData.cc index 15f310859dd..ae86bf9fa9b 100644 --- a/src/QmlControls/InstrumentValueData.cc +++ b/src/QmlControls/InstrumentValueData.cc @@ -29,9 +29,8 @@ InstrumentValueData::InstrumentValueData(FactValueGrid* factValueGrid, QObject* : QObject (parent) , _factValueGrid(factValueGrid) { - MultiVehicleManager* multiVehicleManager = qgcApp()->toolbox()->multiVehicleManager(); - connect(multiVehicleManager, &MultiVehicleManager::activeVehicleChanged, this, &InstrumentValueData::_activeVehicleChanged); - _activeVehicleChanged(multiVehicleManager->activeVehicle()); + connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &InstrumentValueData::_activeVehicleChanged); + _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle()); connect(this, &InstrumentValueData::rangeTypeChanged, this, &InstrumentValueData::_resetRangeInfo); connect(this, &InstrumentValueData::rangeTypeChanged, this, &InstrumentValueData::_updateRanges); @@ -48,7 +47,7 @@ void InstrumentValueData::_activeVehicleChanged(Vehicle* activeVehicle) } if (!activeVehicle) { - activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->offlineEditingVehicle(); + activeVehicle = MultiVehicleManager::instance()->offlineEditingVehicle(); } _activeVehicle = activeVehicle; diff --git a/src/QmlControls/QGroundControlQmlGlobal.cc b/src/QmlControls/QGroundControlQmlGlobal.cc index ce65ccd9f4d..6f0a1e6d481 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.cc +++ b/src/QmlControls/QGroundControlQmlGlobal.cc @@ -41,6 +41,7 @@ #include "ToolStripAction.h" #include "ToolStripActionList.h" #include "VideoManager.h" +#include "MultiVehicleManager.h" #ifndef NO_SERIAL_LINK #include "GPSManager.h" #include "GPSRtk.h" @@ -113,6 +114,7 @@ QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app, QGCToolbox , _missionCommandTree(MissionCommandTree::instance()) , _videoManager(VideoManager::instance()) , _linkManager(LinkManager::instance()) + , _multiVehicleManager(MultiVehicleManager::instance()) #ifndef QGC_AIRLINK_DISABLED , _airlinkManager(AirLinkManager::instance()) #endif @@ -159,7 +161,6 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox) { QGCTool::setToolbox(toolbox); - _multiVehicleManager = toolbox->multiVehicleManager(); _corePlugin = toolbox->corePlugin(); _settingsManager = toolbox->settingsManager(); #ifndef NO_SERIAL_LINK diff --git a/src/QmlControls/QGroundControlQmlGlobal.h b/src/QmlControls/QGroundControlQmlGlobal.h index ecdcbde8c4f..735735a63bc 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.h +++ b/src/QmlControls/QGroundControlQmlGlobal.h @@ -257,6 +257,8 @@ class QGroundControlQmlGlobal : public QGCTool QGCPositionManager* _qgcPositionManager = nullptr; MissionCommandTree* _missionCommandTree = nullptr; VideoManager* _videoManager = nullptr; + LinkManager* _linkManager = nullptr; + MultiVehicleManager* _multiVehicleManager = nullptr; #ifndef QGC_AIRLINK_DISABLED AirLinkManager* _airlinkManager = nullptr; #endif @@ -265,8 +267,6 @@ class QGroundControlQmlGlobal : public QGCTool #endif double _flightMapInitialZoom = 17.0; - LinkManager* _linkManager = nullptr; - MultiVehicleManager* _multiVehicleManager = nullptr; QGCCorePlugin* _corePlugin = nullptr; SettingsManager* _settingsManager = nullptr; #ifndef NO_SERIAL_LINK diff --git a/src/QmlControls/RCToParamDialogController.cc b/src/QmlControls/RCToParamDialogController.cc index 3b5f16c5d63..dd8600c4257 100644 --- a/src/QmlControls/RCToParamDialogController.cc +++ b/src/QmlControls/RCToParamDialogController.cc @@ -54,7 +54,7 @@ void RCToParamDialogController::setTuningFact(Fact *tuningFact) _maxFact->setRawValue(_tuningFact->rawMax().toDouble()); (void) connect(_tuningFact, &Fact::vehicleUpdated, this, &RCToParamDialogController::_parameterUpdated); - qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->parameterManager()->refreshParameter(ParameterManager::defaultComponentId, _tuningFact->name()); + MultiVehicleManager::instance()->activeVehicle()->parameterManager()->refreshParameter(ParameterManager::defaultComponentId, _tuningFact->name()); } void RCToParamDialogController::_parameterUpdated() diff --git a/src/Settings/APMMavlinkStreamRateSettings.cc b/src/Settings/APMMavlinkStreamRateSettings.cc index 73b1d77d7ce..31ac83d52b6 100644 --- a/src/Settings/APMMavlinkStreamRateSettings.cc +++ b/src/Settings/APMMavlinkStreamRateSettings.cc @@ -37,7 +37,7 @@ DECLARE_SETTINGSFACT(APMMavlinkStreamRateSettings, streamRateExtra3) void APMMavlinkStreamRateSettings::_updateStreamRateWorker(MAV_DATA_STREAM mavStream, QVariant rateVar) { - Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle(); + Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle(); if (activeVehicle) { int streamRate = rateVar.toInt(); diff --git a/src/Vehicle/Autotune.h b/src/Vehicle/Autotune.h index d6edbf738d3..7e1afdd1422 100644 --- a/src/Vehicle/Autotune.h +++ b/src/Vehicle/Autotune.h @@ -10,7 +10,7 @@ #pragma once #include "Vehicle.h" -#include "QGCMAVLink.h" +#include "MAVLinkLib.h" #include diff --git a/src/Vehicle/CMakeLists.txt b/src/Vehicle/CMakeLists.txt index a1ce087958a..49c65ebbb93 100644 --- a/src/Vehicle/CMakeLists.txt +++ b/src/Vehicle/CMakeLists.txt @@ -45,7 +45,6 @@ target_link_libraries(Vehicle Joystick MockLink PositionManager - Utilities UTMSP VideoManager PUBLIC @@ -58,7 +57,7 @@ target_link_libraries(Vehicle LibEventsWrapper MAVLink MissionManager - QGC + Utilities VehicleFactGroups ) diff --git a/src/Vehicle/InitialConnectStateMachine.h b/src/Vehicle/InitialConnectStateMachine.h index 7a6cb07f12c..5427d70a5bc 100644 --- a/src/Vehicle/InitialConnectStateMachine.h +++ b/src/Vehicle/InitialConnectStateMachine.h @@ -10,7 +10,7 @@ #pragma once #include "StateMachine.h" -#include "QGCMAVLink.h" +#include "MAVLinkLib.h" #include "Vehicle.h" #include diff --git a/src/Vehicle/MultiVehicleManager.cc b/src/Vehicle/MultiVehicleManager.cc index f76b5111cf8..1e03a5ce2ad 100644 --- a/src/Vehicle/MultiVehicleManager.cc +++ b/src/Vehicle/MultiVehicleManager.cc @@ -18,71 +18,90 @@ #include "Vehicle.h" #include "VehicleLinkManager.h" #include "Autotune.h" +#include "LinkInterface.h" #include "RemoteIDManager.h" #include "VehicleObjectAvoidance.h" #include "TrajectoryPoints.h" +#include "QmlObjectListModel.h" #if defined (Q_OS_IOS) || defined(Q_OS_ANDROID) #include "MobileScreenMgr.h" #endif #include "QGCLoggingCategory.h" +#include +#include #include -QGC_LOGGING_CATEGORY(MultiVehicleManagerLog, "MultiVehicleManagerLog") +QGC_LOGGING_CATEGORY(MultiVehicleManagerLog, "qgc.vehicle.multivehiclemanager") -MultiVehicleManager::MultiVehicleManager(QGCApplication* app, QGCToolbox* toolbox) - : QGCTool(app, toolbox) - , _activeVehicleAvailable(false) - , _parameterReadyVehicleAvailable(false) - , _activeVehicle(nullptr) - , _offlineEditingVehicle(nullptr) - , _gcsHeartbeatEnabled(true) +Q_APPLICATION_STATIC(MultiVehicleManager, _multiVehicleManagerInstance); + +MultiVehicleManager::MultiVehicleManager(QObject *parent) + : QObject(parent) + , _gcsHeartbeatTimer(new QTimer(this)) + , _offlineEditingVehicle(new Vehicle(Vehicle::MAV_AUTOPILOT_TRACK, Vehicle::MAV_TYPE_TRACK, this)) + , _vehicles(new QmlObjectListModel(this)) { - QSettings settings; - _gcsHeartbeatEnabled = settings.value(_gcsHeartbeatEnabledKey, true).toBool(); - _gcsHeartbeatTimer.setInterval(_gcsHeartbeatRateMSecs); - _gcsHeartbeatTimer.setSingleShot(false); + // qCDebug(MultiVehicleManagerLog) << Q_FUNC_INFO << this; } -void MultiVehicleManager::setToolbox(QGCToolbox *toolbox) +MultiVehicleManager::~MultiVehicleManager() { - QGCTool::setToolbox(toolbox); + // qCDebug(MultiVehicleManagerLog) << Q_FUNC_INFO << this; +} - QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); - qmlRegisterUncreatableType ("QGroundControl.MultiVehicleManager", 1, 0, "MultiVehicleManager", "Reference only"); - qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "Vehicle", "Reference only"); - qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "VehicleLinkManager", "Reference only"); - qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "Autotune", "Reference only"); - qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "RemoteIDManager", "Reference only"); - qmlRegisterUncreatableType ("QGroundControl.FlightMap", 1, 0, "TrajectoryPoints", "Reference only"); - qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "VehicleObjectAvoidance", "Reference only"); +MultiVehicleManager *MultiVehicleManager::instance() +{ + return _multiVehicleManagerInstance(); +} - qRegisterMetaType("MavCmdResultFailureCode_t"); +void MultiVehicleManager::registerQmlTypes() +{ + (void) qmlRegisterUncreatableType ("QGroundControl.MultiVehicleManager", 1, 0, "MultiVehicleManager", "Reference only"); + (void) qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "Vehicle", "Reference only"); + (void) qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "VehicleLinkManager", "Reference only"); + (void) qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "Autotune", "Reference only"); + (void) qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "RemoteIDManager", "Reference only"); + (void) qmlRegisterUncreatableType ("QGroundControl.FlightMap", 1, 0, "TrajectoryPoints", "Reference only"); + (void) qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "VehicleObjectAvoidance", "Reference only"); + (void) qRegisterMetaType("MavCmdResultFailureCode_t"); +} - connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::vehicleHeartbeatInfo, this, &MultiVehicleManager::_vehicleHeartbeatInfo); - connect(&_gcsHeartbeatTimer, &QTimer::timeout, this, &MultiVehicleManager::_sendGCSHeartbeat); +void MultiVehicleManager::init() +{ + if (_initialized) { + return; + } + + (void) connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::vehicleHeartbeatInfo, this, &MultiVehicleManager::_vehicleHeartbeatInfo); + + _gcsHeartbeatTimer->setInterval(kGCSHeartbeatRateMSecs); + _gcsHeartbeatTimer->setSingleShot(false); + (void) connect(_gcsHeartbeatTimer, &QTimer::timeout, this, &MultiVehicleManager::_sendGCSHeartbeat); + QSettings settings; + _gcsHeartbeatEnabled = settings.value(kGCSHeartbeatEnabledKey, true).toBool(); if (_gcsHeartbeatEnabled) { - _gcsHeartbeatTimer.start(); + _gcsHeartbeatTimer->start(); } - _offlineEditingVehicle = new Vehicle(Vehicle::MAV_AUTOPILOT_TRACK, Vehicle::MAV_TYPE_TRACK, this); + _initialized = true; } void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType) { if (componentId != MAV_COMP_ID_AUTOPILOT1) { // Don't create vehicles for components other than the autopilot - qCDebug(MultiVehicleManagerLog()) << "Ignoring heartbeat from unknown component port:vehicleId:componentId:fwType:vehicleType" - << link->linkConfiguration()->name() - << vehicleId - << componentId - << vehicleFirmwareType - << vehicleType; + qCDebug(MultiVehicleManagerLog) << "Ignoring heartbeat from unknown component port:vehicleId:componentId:fwType:vehicleType" + << link->linkConfiguration()->name() + << vehicleId + << componentId + << vehicleFirmwareType + << vehicleType; return; } -#if !defined(NO_ARDUPILOT_DIALECT) +#ifndef NO_ARDUPILOT_DIALECT // 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. @@ -91,13 +110,6 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle } #endif - if (_vehicles.count() > 0 && !qgcApp()->toolbox()->corePlugin()->options()->multiVehicleEnabled()) { - return; - } - if (_ignoreVehicleIds.contains(vehicleId) || getVehicleById(vehicleId) || vehicleId == 0) { - return; - } - switch (vehicleType) { case MAV_TYPE_GCS: case MAV_TYPE_ONBOARD_CONTROLLER: @@ -106,27 +118,34 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle // These are not vehicles, so don't create a vehicle for them return; default: - // All other MAV_TYPEs create vehicles break; } - qCDebug(MultiVehicleManagerLog()) << "Adding new vehicle link:vehicleId:componentId:vehicleFirmwareType:vehicleType " - << link->linkConfiguration()->name() - << vehicleId - << componentId - << vehicleFirmwareType - << vehicleType; + if ((_vehicles->count() > 0) && !qgcApp()->toolbox()->corePlugin()->options()->multiVehicleEnabled()) { + return; + } + + if (_ignoreVehicleIds.contains(vehicleId) || getVehicleById(vehicleId) || (vehicleId == 0)) { + return; + } + + qCDebug(MultiVehicleManagerLog) << "Adding new vehicle link:vehicleId:componentId:vehicleFirmwareType:vehicleType " + << link->linkConfiguration()->name() + << vehicleId + << componentId + << vehicleFirmwareType + << vehicleType; 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)); + qgcApp()->showAppMessage(tr("Warning: A vehicle is using the same system id as %1: %2").arg(QCoreApplication::applicationName()).arg(vehicleId)); } - Vehicle* vehicle = new Vehicle(link, vehicleId, componentId, (MAV_AUTOPILOT)vehicleFirmwareType, (MAV_TYPE)vehicleType, this); - connect(vehicle, &Vehicle::requestProtocolVersion, this, &MultiVehicleManager::_requestProtocolVersion); - connect(vehicle->vehicleLinkManager(), &VehicleLinkManager::allLinksRemoved, this, &MultiVehicleManager::_deleteVehiclePhase1); - connect(vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &MultiVehicleManager::_vehicleParametersReadyChanged); + Vehicle *const vehicle = new Vehicle(link, vehicleId, componentId, (MAV_AUTOPILOT)vehicleFirmwareType, (MAV_TYPE)vehicleType, this); + (void) connect(vehicle, &Vehicle::requestProtocolVersion, this, &MultiVehicleManager::_requestProtocolVersion); + (void) connect(vehicle->vehicleLinkManager(), &VehicleLinkManager::allLinksRemoved, this, &MultiVehicleManager::_deleteVehiclePhase1); + (void) connect(vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &MultiVehicleManager::_vehicleParametersReadyChanged); - _vehicles.append(vehicle); + _vehicles->append(vehicle); // Send QGC heartbeat ASAP, this allows PX4 to start accepting commands _sendGCSHeartbeat(); @@ -135,38 +154,32 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle emit vehicleAdded(vehicle); - if (_vehicles.count() > 1) { + if (_vehicles->count() > 1) { qgcApp()->showAppMessage(tr("Connected to Vehicle %1").arg(vehicleId)); } else { setActiveVehicle(vehicle); } #if defined (Q_OS_IOS) || defined(Q_OS_ANDROID) - if(_vehicles.count() == 1) { - //-- Once a vehicle is connected, keep screen from going off + if (_vehicles->count() == 1) { qCDebug(MultiVehicleManagerLog) << "QAndroidJniObject::keepScreenOn"; MobileScreenMgr::setKeepScreenOn(true); } #endif - } -/// This slot is connected to the Vehicle::requestProtocolVersion signal such that the vehicle manager -/// tries to switch MAVLink to v2 if all vehicles support it -void MultiVehicleManager::_requestProtocolVersion(unsigned version) +void MultiVehicleManager::_requestProtocolVersion(unsigned version) const { - unsigned maxversion = 0; - - if (_vehicles.count() == 0) { + if (_vehicles->count() == 0) { MAVLinkProtocol::instance()->setVersion(version); return; } - for (int i=0; i<_vehicles.count(); i++) { - - Vehicle *v = qobject_cast(_vehicles[i]); - if (v && v->maxProtoVersion() > maxversion) { - maxversion = v->maxProtoVersion(); + unsigned maxversion = 0; + for (int i = 0; i < _vehicles->count(); i++) { + const Vehicle *const vehicle = qobject_cast(_vehicles->get(i)); + if (vehicle && (vehicle->maxProtoVersion() > maxversion)) { + maxversion = vehicle->maxProtoVersion(); } } @@ -175,38 +188,30 @@ void MultiVehicleManager::_requestProtocolVersion(unsigned version) } } -/// This slot is connected to the Vehicle::allLinksDestroyed signal such that the Vehicle is deleted -/// and all other right things happen when the Vehicle goes away. -void MultiVehicleManager::_deleteVehiclePhase1(Vehicle* vehicle) +void MultiVehicleManager::_deleteVehiclePhase1(Vehicle *vehicle) { - qCDebug(MultiVehicleManagerLog) << "_deleteVehiclePhase1" << vehicle; + qCDebug(MultiVehicleManagerLog) << Q_FUNC_INFO << vehicle; - _vehiclesBeingDeleted << vehicle; - - // Remove from map bool found = false; - for (int i=0; i<_vehicles.count(); i++) { - if (_vehicles[i] == vehicle) { - _vehicles.removeAt(i); + for (int i = 0; i < _vehicles->count(); i++) { + if (_vehicles->get(i) == vehicle) { + (void) _vehicles->removeAt(i); found = true; break; } } + if (!found) { - qWarning() << "Vehicle not found in map!"; + qCWarning(MultiVehicleManagerLog) << "Vehicle not found in map!"; } - // First we must signal that a vehicle is no longer available. - _activeVehicleAvailable = false; - _parameterReadyVehicleAvailable = false; - emit activeVehicleAvailableChanged(false); - emit parameterReadyVehicleAvailableChanged(false); + _setActiveVehicleAvailable(false); + _setParameterReadyVehicleAvailable(false); emit vehicleRemoved(vehicle); vehicle->prepareDelete(); #if defined (Q_OS_IOS) || defined(Q_OS_ANDROID) - if(_vehicles.count() == 0) { - //-- Once no vehicles are connected, we no longer need to keep screen from going off + if (_vehicles->count() == 0) { qCDebug(MultiVehicleManagerLog) << "QAndroidJniObject::restoreScreenOn"; MobileScreenMgr::setKeepScreenOn(false); } @@ -218,38 +223,38 @@ void MultiVehicleManager::_deleteVehiclePhase1(Vehicle* vehicle) // until we get back to the main loop. So we set a short timer which will then fire after Qt has finished // doing all of its internal nastiness to clean up the Qml. This works for both the normal running case // as well as the unit testing case which of course has a different signal flow! - QTimer::singleShot(20, this, &MultiVehicleManager::_deleteVehiclePhase2); + QTimer::singleShot(20, this, [this, vehicle]() { + _deleteVehiclePhase2(vehicle); + }); } -void MultiVehicleManager::_deleteVehiclePhase2(void) +void MultiVehicleManager::_deleteVehiclePhase2(Vehicle *vehicle) { - qCDebug(MultiVehicleManagerLog) << "_deleteVehiclePhase2" << _vehiclesBeingDeleted[0]; + qCDebug(MultiVehicleManagerLog) << Q_FUNC_INFO << vehicle; /// Qml has been notified of vehicle about to go away and should be disconnected from it by now. /// This means we can now clear the active vehicle property and delete the Vehicle for real. - Vehicle* newActiveVehicle = nullptr; - if (_vehicles.count()) { - newActiveVehicle = qobject_cast(_vehicles[0]); + Vehicle *newActiveVehicle = nullptr; + if (_vehicles->count() > 0) { + newActiveVehicle = qobject_cast(_vehicles->get(0)); } - _activeVehicle = newActiveVehicle; - emit activeVehicleChanged(newActiveVehicle); + _setActiveVehicle(newActiveVehicle); if (_activeVehicle) { - emit activeVehicleAvailableChanged(true); + _setActiveVehicleAvailable(true); if (_activeVehicle->parameterManager()->parametersReady()) { - emit parameterReadyVehicleAvailableChanged(true); + _setParameterReadyVehicleAvailable(true); } } - delete _vehiclesBeingDeleted[0]; - _vehiclesBeingDeleted.removeAt(0); + vehicle->deleteLater(); } -void MultiVehicleManager::setActiveVehicle(Vehicle* vehicle) +void MultiVehicleManager::setActiveVehicle(Vehicle *vehicle) { - qCDebug(MultiVehicleManagerLog) << "setActiveVehicle" << vehicle; + qCDebug(MultiVehicleManagerLog) << Q_FUNC_INFO << vehicle; if (vehicle != _activeVehicle) { if (_activeVehicle) { @@ -258,83 +263,79 @@ void MultiVehicleManager::setActiveVehicle(Vehicle* vehicle) // First we must signal that there is no active vehicle available. This will disconnect // any existing ui from the currently active vehicle. - _activeVehicleAvailable = false; - _parameterReadyVehicleAvailable = false; - emit activeVehicleAvailableChanged(false); - emit parameterReadyVehicleAvailableChanged(false); + _setActiveVehicleAvailable(false); + _setParameterReadyVehicleAvailable(false); } - // See explanation in _deleteVehiclePhase1 - _vehicleBeingSetActive = vehicle; - QTimer::singleShot(20, this, &MultiVehicleManager::_setActiveVehiclePhase2); + QTimer::singleShot(20, this, [this, vehicle]() { + _setActiveVehiclePhase2(vehicle); + }); } } -void MultiVehicleManager::_setActiveVehiclePhase2(void) +void MultiVehicleManager::_setActiveVehiclePhase2(Vehicle *vehicle) { - qCDebug(MultiVehicleManagerLog) << "_setActiveVehiclePhase2 _vehicleBeingSetActive" << _vehicleBeingSetActive; - - //-- Keep track of current vehicle's coordinates - if(_activeVehicle) { - disconnect(_activeVehicle, &Vehicle::coordinateChanged, this, &MultiVehicleManager::_coordinateChanged); - } - if(_vehicleBeingSetActive) { - connect(_vehicleBeingSetActive, &Vehicle::coordinateChanged, this, &MultiVehicleManager::_coordinateChanged); - } + qCDebug(MultiVehicleManagerLog) << Q_FUNC_INFO << vehicle; - // Now we signal the new active vehicle - _activeVehicle = _vehicleBeingSetActive; - emit activeVehicleChanged(_activeVehicle); + _setActiveVehicle(vehicle); - // And finally vehicle availability if (_activeVehicle) { - _activeVehicleAvailable = true; - emit activeVehicleAvailableChanged(true); + _setActiveVehicleAvailable(true); if (_activeVehicle->parameterManager()->parametersReady()) { - _parameterReadyVehicleAvailable = true; - emit parameterReadyVehicleAvailableChanged(true); + _setParameterReadyVehicleAvailable(true); } } } -void MultiVehicleManager::_coordinateChanged(QGeoCoordinate coordinate) -{ - _lastKnownLocation = coordinate; - emit lastKnownLocationChanged(); -} - void MultiVehicleManager::_vehicleParametersReadyChanged(bool parametersReady) { - auto* paramMgr = qobject_cast(sender()); - + ParameterManager *const paramMgr = qobject_cast(sender()); if (!paramMgr) { - qWarning() << "Dynamic cast failed!"; return; } if (paramMgr->vehicle() == _activeVehicle) { - _parameterReadyVehicleAvailable = parametersReady; - emit parameterReadyVehicleAvailableChanged(parametersReady); + _setParameterReadyVehicleAvailable(parametersReady); } } -void MultiVehicleManager::saveSetting(const QString &name, const QString& value) +void MultiVehicleManager::_sendGCSHeartbeat() { - QSettings settings; - settings.setValue(name, value); -} + const QList sharedLinks = LinkManager::instance()->links(); + for (const SharedLinkInterfacePtr link: sharedLinks) { + if (!link->isConnected()) { + continue; + } -QString MultiVehicleManager::loadSetting(const QString &name, const QString& defaultValue) -{ - QSettings settings; - return settings.value(name, defaultValue).toString(); + const SharedLinkConfigurationPtr linkConfiguration = link->linkConfiguration(); + if (linkConfiguration->isHighLatency()) { + continue; + } + + mavlink_message_t message{}; + (void) mavlink_msg_heartbeat_pack_chan( + MAVLinkProtocol::instance()->getSystemId(), + MAVLinkProtocol::instance()->getComponentId(), + link->mavlinkChannel(), + &message, + MAV_TYPE_GCS, + MAV_AUTOPILOT_INVALID, + MAV_MODE_MANUAL_ARMED, + 0, + MAV_STATE_ACTIVE + ); + + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + const uint16_t len = mavlink_msg_to_send_buffer(buffer, &message); + (void) link->writeBytesThreadSafe(reinterpret_cast(buffer), len); + } } -Vehicle* MultiVehicleManager::getVehicleById(int vehicleId) +Vehicle *MultiVehicleManager::getVehicleById(int vehicleId) const { - for (int i=0; i< _vehicles.count(); i++) { - Vehicle* vehicle = qobject_cast(_vehicles[i]); + for (int i = 0; i < _vehicles->count(); i++) { + Vehicle *const vehicle = qobject_cast(_vehicles->get(i)); if (vehicle->id() == vehicleId) { return vehicle; } @@ -343,46 +344,43 @@ Vehicle* MultiVehicleManager::getVehicleById(int vehicleId) return nullptr; } -void MultiVehicleManager::setGcsHeartbeatEnabled(bool gcsHeartBeatEnabled) +void MultiVehicleManager::_setGcsHeartbeatEnabled(bool gcsHeartBeatEnabled) { if (gcsHeartBeatEnabled != _gcsHeartbeatEnabled) { _gcsHeartbeatEnabled = gcsHeartBeatEnabled; emit gcsHeartBeatEnabledChanged(gcsHeartBeatEnabled); QSettings settings; - settings.setValue(_gcsHeartbeatEnabledKey, gcsHeartBeatEnabled); + settings.setValue(kGCSHeartbeatEnabledKey, gcsHeartBeatEnabled); if (gcsHeartBeatEnabled) { - _gcsHeartbeatTimer.start(); + _gcsHeartbeatTimer->start(); } else { - _gcsHeartbeatTimer.stop(); + _gcsHeartbeatTimer->stop(); } } } -void MultiVehicleManager::_sendGCSHeartbeat(void) +void MultiVehicleManager::_setActiveVehicle(Vehicle *vehicle) { - QList sharedLinks = LinkManager::instance()->links(); - - // Send a heartbeat out on each link - for (int i=0; ilinkConfiguration(); - if (link->isConnected() && linkConfiguration && !linkConfiguration->isHighLatency()) { - mavlink_message_t message; - mavlink_msg_heartbeat_pack_chan(MAVLinkProtocol::instance()->getSystemId(), - MAVLinkProtocol::getComponentId(), - link->mavlinkChannel(), - &message, - MAV_TYPE_GCS, // MAV_TYPE - MAV_AUTOPILOT_INVALID, // MAV_AUTOPILOT - MAV_MODE_MANUAL_ARMED, // MAV_MODE - 0, // custom mode - MAV_STATE_ACTIVE); // MAV_STATE - - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - int len = mavlink_msg_to_send_buffer(buffer, &message); - link->writeBytesThreadSafe((const char*)buffer, len); - } + if (vehicle != _activeVehicle) { + _activeVehicle = vehicle; + emit activeVehicleChanged(vehicle); + } +} + +void MultiVehicleManager::_setActiveVehicleAvailable(bool activeVehicleAvailable) +{ + if (activeVehicleAvailable != _activeVehicleAvailable) { + _activeVehicleAvailable = activeVehicleAvailable; + emit activeVehicleAvailableChanged(activeVehicleAvailable); + } +} + +void MultiVehicleManager::_setParameterReadyVehicleAvailable(bool parametersReady) +{ + if (parametersReady != _parameterReadyVehicleAvailable) { + _parameterReadyVehicleAvailable = parametersReady; + parameterReadyVehicleAvailableChanged(parametersReady); } } diff --git a/src/Vehicle/MultiVehicleManager.h b/src/Vehicle/MultiVehicleManager.h index 28049f6bafc..fc4cf5057d4 100644 --- a/src/Vehicle/MultiVehicleManager.h +++ b/src/Vehicle/MultiVehicleManager.h @@ -13,105 +13,80 @@ #pragma once -#include -#include +#include #include -#include "QGCToolbox.h" -#include "QmlObjectListModel.h" -#include "MAVLinkLib.h" - -class QGCApplication; class LinkInterface; class Vehicle; +class QmlObjectListModel; +class QTimer; Q_DECLARE_LOGGING_CATEGORY(MultiVehicleManagerLog) -class MultiVehicleManager : public QGCTool +class MultiVehicleManager : public QObject { Q_OBJECT + Q_MOC_INCLUDE("QmlObjectListModel.h") + Q_MOC_INCLUDE("LinkInterface.h") Q_MOC_INCLUDE("Vehicle.h") + Q_PROPERTY(bool activeVehicleAvailable READ _getActiveVehicleAvailable NOTIFY activeVehicleAvailableChanged) + Q_PROPERTY(bool parameterReadyVehicleAvailable READ _getParameterReadyVehicleAvailable NOTIFY parameterReadyVehicleAvailableChanged) + Q_PROPERTY(Vehicle *activeVehicle READ activeVehicle WRITE setActiveVehicle NOTIFY activeVehicleChanged) + Q_PROPERTY(QmlObjectListModel *vehicles READ vehicles CONSTANT) + Q_PROPERTY(bool gcsHeartBeatEnabled READ _getGcsHeartbeatEnabled WRITE _setGcsHeartbeatEnabled NOTIFY gcsHeartBeatEnabledChanged) + Q_PROPERTY(Vehicle *offlineEditingVehicle READ offlineEditingVehicle CONSTANT) public: - MultiVehicleManager(QGCApplication* app, QGCToolbox* toolbox); - - Q_INVOKABLE void saveSetting (const QString &key, const QString& value); - Q_INVOKABLE QString loadSetting (const QString &key, const QString& defaultValue); - - Q_PROPERTY(bool activeVehicleAvailable READ activeVehicleAvailable NOTIFY activeVehicleAvailableChanged) - Q_PROPERTY(bool parameterReadyVehicleAvailable READ parameterReadyVehicleAvailable NOTIFY parameterReadyVehicleAvailableChanged) - Q_PROPERTY(Vehicle* activeVehicle READ activeVehicle WRITE setActiveVehicle NOTIFY activeVehicleChanged) - Q_PROPERTY(QmlObjectListModel* vehicles READ vehicles CONSTANT) - Q_PROPERTY(bool gcsHeartBeatEnabled READ gcsHeartbeatEnabled WRITE setGcsHeartbeatEnabled NOTIFY gcsHeartBeatEnabledChanged) - Q_PROPERTY(Vehicle* offlineEditingVehicle READ offlineEditingVehicle CONSTANT) - Q_PROPERTY(QGeoCoordinate lastKnownLocation READ lastKnownLocation NOTIFY lastKnownLocationChanged) //< Current vehicles last know location - - // Methods - - Q_INVOKABLE Vehicle* getVehicleById(int vehicleId); - - // Property accessors - - bool activeVehicleAvailable(void) const{ return _activeVehicleAvailable; } - - bool parameterReadyVehicleAvailable(void) const{ return _parameterReadyVehicleAvailable; } - - Vehicle* activeVehicle(void) { return _activeVehicle; } - void setActiveVehicle(Vehicle* vehicle); + explicit MultiVehicleManager(QObject *parent = nullptr); + ~MultiVehicleManager(); - QmlObjectListModel* vehicles(void) { return &_vehicles; } + static MultiVehicleManager *instance(); + static void registerQmlTypes(); - bool gcsHeartbeatEnabled(void) const { return _gcsHeartbeatEnabled; } - void setGcsHeartbeatEnabled(bool gcsHeartBeatEnabled); - - Vehicle* offlineEditingVehicle(void) { return _offlineEditingVehicle; } - - // Override from QGCTool - virtual void setToolbox(QGCToolbox *toolbox); - - QGeoCoordinate lastKnownLocation () { return _lastKnownLocation; } + void init(); + Q_INVOKABLE Vehicle *getVehicleById(int vehicleId) const; + QmlObjectListModel *vehicles() const { return _vehicles; } + Vehicle *offlineEditingVehicle() const { return _offlineEditingVehicle; } + Vehicle *activeVehicle() const { return _activeVehicle; } + void setActiveVehicle(Vehicle *vehicle); signals: - void vehicleAdded (Vehicle* vehicle); - void vehicleRemoved (Vehicle* vehicle); - void activeVehicleAvailableChanged (bool activeVehicleAvailable); + void vehicleAdded(Vehicle *vehicle); + void vehicleRemoved(Vehicle *vehicle); + void activeVehicleAvailableChanged(bool activeVehicleAvailable); void parameterReadyVehicleAvailableChanged(bool parameterReadyVehicleAvailable); - void activeVehicleChanged (Vehicle* activeVehicle); - void gcsHeartBeatEnabledChanged (bool gcsHeartBeatEnabled); - void lastKnownLocationChanged (); -#ifndef DOXYGEN_SKIP - void _deleteVehiclePhase2Signal (void); -#endif + void activeVehicleChanged(Vehicle *activeVehicle); + void gcsHeartBeatEnabledChanged(bool gcsHeartBeatEnabled); private slots: - void _deleteVehiclePhase1 (Vehicle* vehicle); - void _deleteVehiclePhase2 (void); - void _setActiveVehiclePhase2 (void); - void _vehicleParametersReadyChanged (bool parametersReady); - void _sendGCSHeartbeat (void); - void _vehicleHeartbeatInfo (LinkInterface* link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType); - void _requestProtocolVersion (unsigned version); - void _coordinateChanged (QGeoCoordinate coordinate); + void _deleteVehiclePhase1(Vehicle *vehicle); /// This slot is connected to the Vehicle::allLinksDestroyed signal such that the Vehicle is deleted and all other right things happen when the Vehicle goes away. + void _deleteVehiclePhase2(Vehicle *vehicle); + void _setActiveVehiclePhase2(Vehicle *vehicle); + void _vehicleParametersReadyChanged(bool parametersReady); + void _sendGCSHeartbeat(); + void _vehicleHeartbeatInfo(LinkInterface *link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType); + void _requestProtocolVersion(unsigned version) const; /// This slot is connected to the Vehicle::requestProtocolVersion signal such that the vehicle manager tries to switch MAVLink to v2 if all vehicles support it private: bool _vehicleExists(int vehicleId); - - bool _activeVehicleAvailable; ///< true: An active vehicle is available - bool _parameterReadyVehicleAvailable; ///< true: An active vehicle with ready parameters is available - Vehicle* _activeVehicle; ///< Currently active vehicle from a ui perspective - Vehicle* _offlineEditingVehicle; ///< Disconnected vechicle used for offline editing - - QList _vehiclesBeingDeleted; ///< List of Vehicles being deleted in queued phases - Vehicle* _vehicleBeingSetActive; ///< Vehicle being set active in queued phases - - QList _ignoreVehicleIds; ///< List of vehicle id for which we ignore further communication - - QmlObjectListModel _vehicles; - - QGeoCoordinate _lastKnownLocation; - - QTimer _gcsHeartbeatTimer; ///< Timer to emit heartbeats - bool _gcsHeartbeatEnabled; ///< Enabled/disable heartbeat emission - static constexpr int _gcsHeartbeatRateMSecs = 1000; ///< Heartbeat rate - static constexpr const char* _gcsHeartbeatEnabledKey = "gcsHeartbeatEnabled"; + void _setActiveVehicle(Vehicle *vehicle); + bool _getGcsHeartbeatEnabled() const { return _gcsHeartbeatEnabled; } + void _setGcsHeartbeatEnabled(bool gcsHeartBeatEnabled); + bool _getActiveVehicleAvailable() const { return _activeVehicleAvailable; } + void _setActiveVehicleAvailable(bool activeVehicleAvailable); + bool _getParameterReadyVehicleAvailable() const { return _parameterReadyVehicleAvailable; } + void _setParameterReadyVehicleAvailable(bool parametersReady); + + QTimer *_gcsHeartbeatTimer = nullptr; ///< Timer to emit heartbeats + Vehicle *_offlineEditingVehicle = nullptr; ///< Disconnected vechicle used for offline editing + QmlObjectListModel *_vehicles = nullptr; + bool _activeVehicleAvailable = false; ///< true: An active vehicle is available + bool _gcsHeartbeatEnabled = false; ///< Enabled/disable heartbeat emission + bool _parameterReadyVehicleAvailable = false; ///< true: An active vehicle with ready parameters is available + Vehicle *_activeVehicle = nullptr; ///< Currently active vehicle from a ui perspective + QList _ignoreVehicleIds; ///< List of vehicle id for which we ignore further communication + bool _initialized = false; + + static constexpr int kGCSHeartbeatRateMSecs = 1000; ///< Heartbeat rate + static constexpr const char *kGCSHeartbeatEnabledKey = "gcsHeartbeatEnabled"; }; diff --git a/src/Vehicle/RemoteIDManager.h b/src/Vehicle/RemoteIDManager.h index a7641ee58a4..f64497b4fd4 100644 --- a/src/Vehicle/RemoteIDManager.h +++ b/src/Vehicle/RemoteIDManager.h @@ -15,7 +15,7 @@ #include #include -#include "QGCMAVLink.h" +#include "MAVLinkLib.h" Q_DECLARE_LOGGING_CATEGORY(RemoteIDManagerLog) diff --git a/src/Vehicle/StandardModes.h b/src/Vehicle/StandardModes.h index 213653ca2c5..d1c55a4e303 100644 --- a/src/Vehicle/StandardModes.h +++ b/src/Vehicle/StandardModes.h @@ -9,8 +9,9 @@ #pragma once -#include "QGCMAVLink.h" +#include "MAVLinkLib.h" +#include #include #include #include diff --git a/src/Vehicle/TerrainProtocolHandler.h b/src/Vehicle/TerrainProtocolHandler.h index bfed199300c..6a5a0bc37ea 100644 --- a/src/Vehicle/TerrainProtocolHandler.h +++ b/src/Vehicle/TerrainProtocolHandler.h @@ -13,7 +13,7 @@ #include #include -#include "QGCMAVLink.h" +#include "MAVLinkLib.h" class QTimer; class TerrainFactGroup; diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 63e49360798..06f864325e5 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -112,7 +112,7 @@ Vehicle::Vehicle(LinkInterface* link, , _terrainProtocolHandler (new TerrainProtocolHandler(this, &_terrainFactGroup, this)) { connect(JoystickManager::instance(), &JoystickManager::activeJoystickChanged, this, &Vehicle::_loadJoystickSettings); - connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &Vehicle::_activeVehicleChanged); + connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &Vehicle::_activeVehicleChanged); qCDebug(VehicleLog) << "Link started with Mavlink " << (MAVLinkProtocol::instance()->getCurrentVersion() >= 200 ? "V2" : "V1"); @@ -128,7 +128,7 @@ Vehicle::Vehicle(LinkInterface* link, } }); - connect(_toolbox->multiVehicleManager(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &Vehicle::_vehicleParamLoaded); + connect(MultiVehicleManager::instance(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &Vehicle::_vehicleParamLoaded); connect(this, &Vehicle::remoteControlRSSIChanged, this, &Vehicle::_remoteControlRSSIChanged); @@ -1540,7 +1540,7 @@ void Vehicle::setJoystickEnabled(bool enabled) // if we are the active vehicle, call start polling on the active joystick // This routes the joystick signals to this vehicle - if (enabled && _toolbox->multiVehicleManager()->activeVehicle() == this){ + if (enabled && MultiVehicleManager::instance()->activeVehicle() == this){ _captureJoystick(); } @@ -1977,7 +1977,7 @@ QString Vehicle::vehicleClassInternalName() const /// Returns the string to speak to identify the vehicle QString Vehicle::_vehicleIdSpeech() { - if (_toolbox->multiVehicleManager()->vehicles()->count() > 1) { + if (MultiVehicleManager::instance()->vehicles()->count() > 1) { return tr("Vehicle %1 ").arg(id()); } else { return QString(); diff --git a/src/VehicleSetup/FirmwareUpgradeController.cc b/src/VehicleSetup/FirmwareUpgradeController.cc index 766148a1e03..960be3892d4 100644 --- a/src/VehicleSetup/FirmwareUpgradeController.cc +++ b/src/VehicleSetup/FirmwareUpgradeController.cc @@ -162,7 +162,7 @@ void FirmwareUpgradeController::startBoardSearch(void) LinkManager::instance()->setConnectionsSuspended(tr("Connect not allowed during Firmware Upgrade.")); // FIXME: Why did we get here with active vehicle? - if (!qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()) { + if (!MultiVehicleManager::instance()->activeVehicle()) { // We have to disconnect any inactive links LinkManager::instance()->disconnectAll(); } diff --git a/src/VehicleSetup/JoystickConfigController.cc b/src/VehicleSetup/JoystickConfigController.cc index 90dd6e4e357..1981f6c1edc 100644 --- a/src/VehicleSetup/JoystickConfigController.cc +++ b/src/VehicleSetup/JoystickConfigController.cc @@ -489,7 +489,7 @@ void JoystickConfigController::_writeCalibration() _stopCalibration(); _setInternalCalibrationValuesFromSettings(); - Vehicle* vehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle(); + Vehicle* vehicle = MultiVehicleManager::instance()->activeVehicle(); if (vehicle) { vehicle->setJoystickEnabled(true); vehicle->saveJoystickSettings(); diff --git a/src/VideoManager/SubtitleWriter.cc b/src/VideoManager/SubtitleWriter.cc index 4a0e590f1c9..1c727824216 100644 --- a/src/VideoManager/SubtitleWriter.cc +++ b/src/VideoManager/SubtitleWriter.cc @@ -115,7 +115,7 @@ void SubtitleWriter::_captureTelemetry() static const float nRows = 3; // number of rows used for displaying data static const int offsetFactor = 700; // Used to simulate a larger resolution and reduce the borders in the layout - auto *vehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle(); + auto *vehicle = MultiVehicleManager::instance()->activeVehicle(); if (!vehicle) { qCWarning(SubtitleWriterLog) << "Attempting to capture fact data with no active vehicle!"; diff --git a/src/VideoManager/VideoManager.cc b/src/VideoManager/VideoManager.cc index a8ba859ae6a..ccdd700c3ff 100644 --- a/src/VideoManager/VideoManager.cc +++ b/src/VideoManager/VideoManager.cc @@ -116,7 +116,7 @@ void VideoManager::init() (void) connect(_videoSettings->tcpUrl(), &Fact::rawValueChanged, this, &VideoManager::_videoSourceChanged); (void) connect(_videoSettings->aspectRatio(), &Fact::rawValueChanged, this, &VideoManager::aspectRatioChanged); (void) connect(_videoSettings->lowLatencyMode(), &Fact::rawValueChanged, this, &VideoManager::_lowLatencyModeChanged); - (void) connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle); + (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &VideoManager::_setActiveVehicle); int index = 0; for (VideoReceiverData &videoReceiver : _videoReceiverData) { diff --git a/src/Viewer3D/Viewer3DQmlBackend.cc b/src/Viewer3D/Viewer3DQmlBackend.cc index a74620666cc..3f9fbcea2a0 100644 --- a/src/Viewer3D/Viewer3DQmlBackend.cc +++ b/src/Viewer3D/Viewer3DQmlBackend.cc @@ -30,10 +30,10 @@ Viewer3DQmlBackend::Viewer3DQmlBackend(QObject *parent) void Viewer3DQmlBackend::init(OsmParser* osmThr) { _osmParserThread = osmThr; - _activeVehicleChangedEvent(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()); + _activeVehicleChangedEvent(MultiVehicleManager::instance()->activeVehicle()); connect(_osmParserThread, &OsmParser::gpsRefChanged, this, &Viewer3DQmlBackend::_gpsRefChangedEvent); - connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &Viewer3DQmlBackend::_activeVehicleChangedEvent); + connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &Viewer3DQmlBackend::_activeVehicleChangedEvent); } void Viewer3DQmlBackend::_activeVehicleChangedEvent(Vehicle *vehicle) diff --git a/test/AnalyzeView/MavlinkLogTest.cc b/test/AnalyzeView/MavlinkLogTest.cc index d5291e02a58..3d7952eaff4 100644 --- a/test/AnalyzeView/MavlinkLogTest.cc +++ b/test/AnalyzeView/MavlinkLogTest.cc @@ -129,7 +129,7 @@ void MavlinkLogTest::_connectLogWorker(bool arm) QDir logSaveDir; if (arm) { - qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->setArmedShowError(true); + MultiVehicleManager::instance()->activeVehicle()->setArmedShowError(true); QTest::qWait(500); // Wait long enough for heartbeat to come through // On Disconnect: We should get a getSaveFileName dialog. diff --git a/test/AutoPilotPlugins/RadioConfigTest.cc b/test/AutoPilotPlugins/RadioConfigTest.cc index c0108755b9c..9f4be463380 100644 --- a/test/AutoPilotPlugins/RadioConfigTest.cc +++ b/test/AutoPilotPlugins/RadioConfigTest.cc @@ -194,7 +194,7 @@ void RadioConfigTest::_init(MAV_AUTOPILOT firmwareType) { _connectMockLink(firmwareType); - _autopilot = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->autopilotPlugin(); + _autopilot = MultiVehicleManager::instance()->activeVehicle()->autopilotPlugin(); Q_ASSERT(_autopilot); // This test is so quick that it tends to finish before the mission item protocol completes. This causes an error to pop up. diff --git a/test/FactSystem/FactSystemTestBase.cc b/test/FactSystem/FactSystemTestBase.cc index 0816b84e92d..5ff5e8d682d 100644 --- a/test/FactSystem/FactSystemTestBase.cc +++ b/test/FactSystem/FactSystemTestBase.cc @@ -17,6 +17,7 @@ #include "QGCApplication.h" #include "ParameterManager.h" #include "AutoPilotPlugin.h" +#include "MAVLinkProtocol.h" #include #include @@ -30,10 +31,11 @@ FactSystemTestBase::FactSystemTestBase(void) void FactSystemTestBase::_init(MAV_AUTOPILOT autopilot) { UnitTest::init(); + MultiVehicleManager::instance()->init(); _connectMockLink(autopilot); - _plugin = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->autopilotPlugin(); + _plugin = MultiVehicleManager::instance()->activeVehicle()->autopilotPlugin(); Q_ASSERT(_plugin); } @@ -100,7 +102,7 @@ void FactSystemTestBase::_qmlUpdate_test(void) // Change the value QVariant paramValue = 12; - qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->parameterManager()->getParameter(ParameterManager::defaultComponentId, "RC_MAP_THROTTLE")->setRawValue(paramValue); + MultiVehicleManager::instance()->activeVehicle()->parameterManager()->getParameter(ParameterManager::defaultComponentId, "RC_MAP_THROTTLE")->setRawValue(paramValue); QTest::qWait(500); // Let the signals flow through diff --git a/test/FactSystem/ParameterManagerTest.cc b/test/FactSystem/ParameterManagerTest.cc index c94fb1c10b2..406bc761b3d 100644 --- a/test/FactSystem/ParameterManagerTest.cc +++ b/test/FactSystem/ParameterManagerTest.cc @@ -23,7 +23,7 @@ void ParameterManagerTest::_noFailureWorker(MockConfiguration::FailureMode_t fai Q_ASSERT(!_mockLink); _mockLink = MockLink::startPX4MockLink(false, failureMode); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); QVERIFY(vehicleMgr); // Wait for the Vehicle to get created @@ -77,7 +77,7 @@ void ParameterManagerTest::_requestListNoResponse(void) Q_ASSERT(!_mockLink); _mockLink = MockLink::startPX4MockLink(false, MockConfiguration::FailParamNoReponseToRequestList); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); QVERIFY(vehicleMgr); // Wait for the Vehicle to get created @@ -112,7 +112,7 @@ void ParameterManagerTest::_requestListMissingParamFail(void) Q_ASSERT(!_mockLink); _mockLink = MockLink::startPX4MockLink(false, MockConfiguration::FailMissingParamOnAllRequests); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); QVERIFY(vehicleMgr); // Wait for the Vehicle to get created @@ -148,7 +148,7 @@ void ParameterManagerTest::_FTPnoFailure() Q_ASSERT(!_mockLink); _mockLink = MockLink::startAPMArduPlaneMockLink(false, MockConfiguration::FailParamNoReponseToRequestList); _mockLink->mockLinkFTP()->enableBinParamFile(true); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); QVERIFY(vehicleMgr); // Wait for the Vehicle to get created @@ -190,7 +190,7 @@ void ParameterManagerTest::_FTPChangeParam() Q_ASSERT(!_mockLink); _mockLink = MockLink::startAPMArduPlaneMockLink(false, MockConfiguration::FailParamNoReponseToRequestList); _mockLink->mockLinkFTP()->enableBinParamFile(true); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); QVERIFY(vehicleMgr); // Wait for the Vehicle to get created diff --git a/test/FollowMe/FollowMeTest.cc b/test/FollowMe/FollowMeTest.cc index b92e5a0c4a7..82a1c177f65 100644 --- a/test/FollowMe/FollowMeTest.cc +++ b/test/FollowMe/FollowMeTest.cc @@ -25,7 +25,7 @@ void FollowMeTest::_testFollowMe() _connectMockLinkNoInitialConnectSequence(); - MultiVehicleManager *vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager *vehicleMgr = MultiVehicleManager::instance(); Vehicle *vehicle = vehicleMgr->activeVehicle(); vehicle->setFlightMode(vehicle->followFlightMode()); qgcApp()->toolbox()->settingsManager()->appSettings()->followTarget()->setRawValue(1); diff --git a/test/MissionManager/MissionControllerManagerTest.cc b/test/MissionManager/MissionControllerManagerTest.cc index 28c3a5796d9..ba5c0866b88 100644 --- a/test/MissionManager/MissionControllerManagerTest.cc +++ b/test/MissionManager/MissionControllerManagerTest.cc @@ -33,7 +33,7 @@ void MissionControllerManagerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareTy // Wait for the Mission Manager to finish it's initial load - _missionManager = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->missionManager(); + _missionManager = MultiVehicleManager::instance()->activeVehicle()->missionManager(); QVERIFY(_missionManager); _rgMissionManagerSignals[newMissionItemsAvailableSignalIndex] = SIGNAL(newMissionItemsAvailable(bool)); diff --git a/test/Vehicle/FTPManagerTest.cc b/test/Vehicle/FTPManagerTest.cc index f5fa0d6fa10..318231ca666 100644 --- a/test/Vehicle/FTPManagerTest.cc +++ b/test/Vehicle/FTPManagerTest.cc @@ -31,7 +31,7 @@ void FTPManagerTest::_testCaseWorker(const TestCase_t& testCase) { _connectMockLinkNoInitialConnectSequence(); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); Vehicle* vehicle = vehicleMgr->activeVehicle(); FTPManager* ftpManager = vehicle->ftpManager(); @@ -146,7 +146,7 @@ void FTPManagerTest::_testListDirectory(void) { _connectMockLinkNoInitialConnectSequence(); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); Vehicle* vehicle = vehicleMgr->activeVehicle(); FTPManager* ftpManager = vehicle->ftpManager(); @@ -169,7 +169,7 @@ void FTPManagerTest::_testListDirectoryNoResponse(void) { _connectMockLinkNoInitialConnectSequence(); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); Vehicle* vehicle = vehicleMgr->activeVehicle(); FTPManager* ftpManager = vehicle->ftpManager(); @@ -192,7 +192,7 @@ void FTPManagerTest::_testListDirectoryNakResponse(void) { _connectMockLinkNoInitialConnectSequence(); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); Vehicle* vehicle = vehicleMgr->activeVehicle(); FTPManager* ftpManager = vehicle->ftpManager(); @@ -215,7 +215,7 @@ void FTPManagerTest::_testListDirectoryNoSecondResponse(void) { _connectMockLinkNoInitialConnectSequence(); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); Vehicle* vehicle = vehicleMgr->activeVehicle(); FTPManager* ftpManager = vehicle->ftpManager(); @@ -238,7 +238,7 @@ void FTPManagerTest::_testListDirectoryNoSecondResponseAllowRetry(void) { _connectMockLinkNoInitialConnectSequence(); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); Vehicle* vehicle = vehicleMgr->activeVehicle(); FTPManager* ftpManager = vehicle->ftpManager(); @@ -261,7 +261,7 @@ void FTPManagerTest::_testListDirectoryNakSecondResponse(void) { _connectMockLinkNoInitialConnectSequence(); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); Vehicle* vehicle = vehicleMgr->activeVehicle(); FTPManager* ftpManager = vehicle->ftpManager(); @@ -284,7 +284,7 @@ void FTPManagerTest::_testListDirectoryBadSequence(void) { _connectMockLinkNoInitialConnectSequence(); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); Vehicle* vehicle = vehicleMgr->activeVehicle(); FTPManager* ftpManager = vehicle->ftpManager(); diff --git a/test/Vehicle/InitialConnectTest.cc b/test/Vehicle/InitialConnectTest.cc index c148b76475e..1f4ab2e7094 100644 --- a/test/Vehicle/InitialConnectTest.cc +++ b/test/Vehicle/InitialConnectTest.cc @@ -39,7 +39,7 @@ void InitialConnectTest::_performTestCases(void) void InitialConnectTest::_boardVendorProductId(void) { - auto *mvm = qgcApp()->toolbox()->multiVehicleManager(); + auto *mvm = MultiVehicleManager::instance(); QSignalSpy activeVehicleSpy{mvm, &MultiVehicleManager::activeVehicleChanged}; auto mockConfig = std::make_shared(QString{"MockLink"}); diff --git a/test/Vehicle/MAVLinkLogManagerTest.cc b/test/Vehicle/MAVLinkLogManagerTest.cc index bbf5dce520b..85dabadeb5f 100644 --- a/test/Vehicle/MAVLinkLogManagerTest.cc +++ b/test/Vehicle/MAVLinkLogManagerTest.cc @@ -22,7 +22,7 @@ void MAVLinkLogManagerTest::_testInitMAVLinkLogManager() { _connectMockLinkNoInitialConnectSequence(); - MultiVehicleManager *const vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager *const vehicleMgr = MultiVehicleManager::instance(); Vehicle *const vehicle = vehicleMgr->activeVehicle(); MAVLinkLogManager *const mavlinkLogManager = new MAVLinkLogManager(vehicle, this); QVERIFY(mavlinkLogManager); diff --git a/test/Vehicle/RequestMessageTest.cc b/test/Vehicle/RequestMessageTest.cc index 6ab81929e9a..bda0743fe83 100644 --- a/test/Vehicle/RequestMessageTest.cc +++ b/test/Vehicle/RequestMessageTest.cc @@ -37,7 +37,7 @@ void RequestMessageTest::_testCaseWorker(TestCase_t& testCase) { _connectMockLinkNoInitialConnectSequence(); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); Vehicle* vehicle = vehicleMgr->activeVehicle(); // Gimbal controller sends message requests when receiving heartbeats, trying to find a gimbal, and it messes with this test so we disable it @@ -82,7 +82,7 @@ void RequestMessageTest::_duplicateCommand(void) MockLink::FailRequestMessageCommandNoResponse, MAV_RESULT_FAILED, Vehicle::RequestMessageFailureDuplicateCommand, 1, false }; - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); Vehicle* vehicle = vehicleMgr->activeVehicle(); _mockLink->clearReceivedMavCommandCounts(); @@ -128,7 +128,7 @@ void RequestMessageTest::_compIdAllFailure(void) MockLink::FailRequestMessageCommandNoResponse, MAV_RESULT_FAILED, Vehicle::RequestMessageFailureCommandError, 0, false }; - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); Vehicle* vehicle = vehicleMgr->activeVehicle(); _mockLink->clearReceivedMavCommandCounts(); diff --git a/test/Vehicle/SendMavCommandWithHandlerTest.cc b/test/Vehicle/SendMavCommandWithHandlerTest.cc index 28d56b3a084..8c0a90405b0 100644 --- a/test/Vehicle/SendMavCommandWithHandlerTest.cc +++ b/test/Vehicle/SendMavCommandWithHandlerTest.cc @@ -43,7 +43,7 @@ void SendMavCommandWithHandlerTest::_mavCmdResultHandler(void* resultHandlerData void SendMavCommandWithHandlerTest::_mavCmdProgressHandler(void* progressHandlerData, int compId, const mavlink_command_ack_t& ack) { TestCase_t* testCase = static_cast(progressHandlerData); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); Vehicle* vehicle = vehicleMgr->activeVehicle(); _progressHandlerCalled = true; @@ -60,7 +60,7 @@ void SendMavCommandWithHandlerTest::_testCaseWorker(TestCase_t& testCase) { _connectMockLinkNoInitialConnectSequence(); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); Vehicle* vehicle = vehicleMgr->activeVehicle(); Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {}; @@ -103,7 +103,7 @@ void SendMavCommandWithHandlerTest::_duplicateCommand(void) MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE, MAV_RESULT_FAILED, 0, Vehicle::MavCmdResultFailureDuplicateCommand, 1 }; - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); Vehicle* vehicle = vehicleMgr->activeVehicle(); Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {}; @@ -145,7 +145,7 @@ void SendMavCommandWithHandlerTest::_compIdAllFailure(void) MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE, MAV_RESULT_FAILED, 0, Vehicle::MavCmdResultFailureDuplicateCommand, 0 }; - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); Vehicle* vehicle = vehicleMgr->activeVehicle(); Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {}; diff --git a/test/Vehicle/SendMavCommandWithSignallingTest.cc b/test/Vehicle/SendMavCommandWithSignallingTest.cc index 9de3ca971f1..84409bc2893 100644 --- a/test/Vehicle/SendMavCommandWithSignallingTest.cc +++ b/test/Vehicle/SendMavCommandWithSignallingTest.cc @@ -28,7 +28,7 @@ void SendMavCommandWithSignallingTest::_testCaseWorker(TestCase_t& testCase) { _connectMockLinkNoInitialConnectSequence(); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); Vehicle* vehicle = vehicleMgr->activeVehicle(); QSignalSpy spyResult(vehicle, &Vehicle::mavCommandResult); @@ -75,7 +75,7 @@ void SendMavCommandWithSignallingTest::_duplicateCommand(void) { _connectMockLinkNoInitialConnectSequence(); - MultiVehicleManager* vehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + MultiVehicleManager* vehicleMgr = MultiVehicleManager::instance(); Vehicle* vehicle = vehicleMgr->activeVehicle(); vehicle->sendMavCommand(MAV_COMP_ID_AUTOPILOT1, MockLink::MAV_CMD_MOCKLINK_NO_RESPONSE, true /* showError */); diff --git a/test/Vehicle/VehicleLinkManagerTest.cc b/test/Vehicle/VehicleLinkManagerTest.cc index b68963677c8..b6d8021545c 100644 --- a/test/Vehicle/VehicleLinkManagerTest.cc +++ b/test/Vehicle/VehicleLinkManagerTest.cc @@ -35,7 +35,7 @@ void VehicleLinkManagerTest::init(void) { UnitTest::init(); - _multiVehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); + _multiVehicleMgr = MultiVehicleManager::instance(); QCOMPARE(LinkManager::instance()->links().count(), 0); QCOMPARE(_multiVehicleMgr->vehicles()->count(), 0); diff --git a/test/qgcunittest/UnitTest.cc b/test/qgcunittest/UnitTest.cc index dfaa407bd9c..85ba0edb807 100644 --- a/test/qgcunittest/UnitTest.cc +++ b/test/qgcunittest/UnitTest.cc @@ -371,7 +371,7 @@ void UnitTest::_connectMockLink(MAV_AUTOPILOT autopilot, MockConfiguration::Fail { Q_ASSERT(!_mockLink); - QSignalSpy spyVehicle(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged); + QSignalSpy spyVehicle(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged); switch (autopilot) { case MAV_AUTOPILOT_PX4: @@ -393,7 +393,7 @@ void UnitTest::_connectMockLink(MAV_AUTOPILOT autopilot, MockConfiguration::Fail // Wait for the Vehicle to get created QCOMPARE(spyVehicle.wait(10000), true); - _vehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle(); + _vehicle = MultiVehicleManager::instance()->activeVehicle(); QVERIFY(_vehicle); if (autopilot != MAV_AUTOPILOT_INVALID) { @@ -406,14 +406,14 @@ void UnitTest::_connectMockLink(MAV_AUTOPILOT autopilot, MockConfiguration::Fail void UnitTest::_disconnectMockLink(void) { if (_mockLink) { - QSignalSpy spyVehicle(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged); + QSignalSpy spyVehicle(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged); _mockLink->disconnect(); _mockLink = nullptr; // Wait for all the vehicle to go away QCOMPARE(spyVehicle.wait(10000), true); - _vehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle(); + _vehicle = MultiVehicleManager::instance()->activeVehicle(); QVERIFY(!_vehicle); } }