diff --git a/QGCApplication.pro b/QGCApplication.pro index a89c6d8af0b236db64ad19f28576ad0d2433e7a6..c47dea6ac60fa082e6f9ac13a2a94e36303c2940 100644 --- a/QGCApplication.pro +++ b/QGCApplication.pro @@ -242,6 +242,7 @@ HEADERS += \ src/QGCQuickWidget.h \ src/QGCSingleton.h \ src/QGCTemporaryFile.h \ + src/QGCToolbox.h \ src/QmlControls/CoordinateVector.h \ src/QmlControls/MavlinkQmlSingleton.h \ src/QmlControls/ParameterEditorController.h \ @@ -356,6 +357,7 @@ SOURCES += \ src/QGCQuickWidget.cc \ src/QGCSingleton.cc \ src/QGCTemporaryFile.cc \ + src/QGCToolbox.cc \ src/QGCGeo.cc \ src/QmlControls/CoordinateVector.cc \ src/QmlControls/ParameterEditorController.cc \ diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.cc b/src/AutoPilotPlugins/AutoPilotPlugin.cc index 177212814e3495f4edb73c4e51e5eb7ee02e5657..08d7a5d27c7f6ce32a55bd579089de235a8689f4 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/AutoPilotPlugin.cc @@ -101,7 +101,7 @@ bool AutoPilotPlugin::setupComplete(void) void AutoPilotPlugin::resetAllParametersToDefaults(void) { mavlink_message_t msg; - MAVLinkProtocol* mavlink = MAVLinkProtocol::instance(); + MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->uas()->getUASID(), 0, MAV_CMD_PREFLIGHT_STORAGE, 0, 2, -1, 0, 0, 0, 0, 0); _vehicle->sendMessage(msg); diff --git a/src/AutoPilotPlugins/AutoPilotPluginManager.cc b/src/AutoPilotPlugins/AutoPilotPluginManager.cc index 7220fa11e81780ab5c1086d1dc913b6e744e6a68..3efc78f482ca2e6e2f1f7d5a461f59a31d63a75e 100644 --- a/src/AutoPilotPlugins/AutoPilotPluginManager.cc +++ b/src/AutoPilotPlugins/AutoPilotPluginManager.cc @@ -29,14 +29,6 @@ #include "APM/APMAutoPilotPlugin.h" #include "Generic/GenericAutoPilotPlugin.h" -IMPLEMENT_QGC_SINGLETON(AutoPilotPluginManager, AutoPilotPluginManager) - -AutoPilotPluginManager::AutoPilotPluginManager(QObject* parent) : - QGCSingleton(parent) -{ - -} - AutoPilotPlugin* AutoPilotPluginManager::newAutopilotPluginForVehicle(Vehicle* vehicle) { switch (vehicle->firmwareType()) { diff --git a/src/AutoPilotPlugins/AutoPilotPluginManager.h b/src/AutoPilotPlugins/AutoPilotPluginManager.h index e2c333332aa880c4593748a948570df71709da95..67e75f005e081b078ba4ebaec383e5734cfee5cf 100644 --- a/src/AutoPilotPlugins/AutoPilotPluginManager.h +++ b/src/AutoPilotPlugins/AutoPilotPluginManager.h @@ -32,23 +32,19 @@ #include #include "AutoPilotPlugin.h" -#include "QGCSingleton.h" #include "Vehicle.h" +#include "QGCToolbox.h" -/// AutoPilotPlugin manager is a singleton which maintains the list of AutoPilotPlugin objects. +class QGCApplication; -class AutoPilotPluginManager : public QGCSingleton +class AutoPilotPluginManager : public QGCTool { Q_OBJECT - - DECLARE_QGC_SINGLETON(AutoPilotPluginManager, AutoPilotPluginManager) public: + AutoPilotPluginManager(QGCApplication* app) : QGCTool(app) { } + AutoPilotPlugin* newAutopilotPluginForVehicle(Vehicle* vehicle); - -private: - /// All access to singleton is through AutoPilotPluginManager::instance - AutoPilotPluginManager(QObject* parent = NULL); }; #endif diff --git a/src/AutoPilotPlugins/PX4/AirframeComponentController.cc b/src/AutoPilotPlugins/PX4/AirframeComponentController.cc index a7ce9a4182421c4571bb3d95e5b6c8dee7a897f1..3fc8a16fd9108e1f6f39c6318735ba84a82729c9 100644 --- a/src/AutoPilotPlugins/PX4/AirframeComponentController.cc +++ b/src/AutoPilotPlugins/PX4/AirframeComponentController.cc @@ -98,7 +98,7 @@ AirframeComponentController::~AirframeComponentController() void AirframeComponentController::changeAutostart(void) { - if (MultiVehicleManager::instance()->vehicles().count() > 1) { + if (qgcApp()->toolbox()->multiVehicleManager()->vehicles().count() > 1) { QGCMessageBox::warning("Airframe Config", "You cannot change airframe configuration while connected to multiple vehicles."); return; } @@ -139,7 +139,7 @@ void AirframeComponentController::_rebootAfterStackUnwind(void) QGC::SLEEP::usleep(500); qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents); } - LinkManager::instance()->disconnectAll(); + qgcApp()->toolbox()->linkManager()->disconnectAll(); qgcApp()->restoreOverrideCursor(); } diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc index 09441f6e8a3eeccee84ea691b7d41650e4b7a6cb..c34fe894b476a37616b7572b557cd745948d4299 100644 --- a/src/FactSystem/Fact.cc +++ b/src/FactSystem/Fact.cc @@ -135,7 +135,6 @@ QString Fact::valueString(void) const switch (type()) { case FactMetaData::valueTypeFloat: - qDebug() << name() << value() << decimalPlaces(); valueString = QString("%1").arg(value().toFloat(), 0, 'g', decimalPlaces()); break; case FactMetaData::valueTypeDouble: diff --git a/src/FactSystem/FactControls/FactPanelController.cc b/src/FactSystem/FactControls/FactPanelController.cc index b828e0771c551896e2d2dd8ef0fb672865ca576e..78e72ff1a582fec90b95ceece9733fc50abd4925 100644 --- a/src/FactSystem/FactControls/FactPanelController.cc +++ b/src/FactSystem/FactControls/FactPanelController.cc @@ -36,7 +36,7 @@ QGC_LOGGING_CATEGORY(FactPanelControllerLog, "FactPanelControllerLog") FactPanelController::FactPanelController(void) : _factPanel(NULL) { - _vehicle = MultiVehicleManager::instance()->activeVehicle(); + _vehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle(); Q_ASSERT(_vehicle); _uas = _vehicle->uas(); diff --git a/src/FactSystem/FactSystem.cc b/src/FactSystem/FactSystem.cc index ae10d1ceefe4d188b61f5677f2039aa2f5d21fd4..68b8b374fcd7c41b9371885d6ac58ee1e2872929 100644 --- a/src/FactSystem/FactSystem.cc +++ b/src/FactSystem/FactSystem.cc @@ -29,19 +29,18 @@ #include -IMPLEMENT_QGC_SINGLETON(FactSystem, FactSystem) - const char* FactSystem::_factSystemQmlUri = "QGroundControl.FactSystem"; -FactSystem::FactSystem(QObject* parent) : - QGCSingleton(parent) +FactSystem::FactSystem(QGCApplication* app) + : QGCTool(app) { - - qmlRegisterType(_factSystemQmlUri, 1, 0, "Fact"); - qmlRegisterType(_factSystemQmlUri, 1, 0, "FactPanelController"); + } -FactSystem::~FactSystem() +void FactSystem::setToolbox(QGCToolbox *toolbox) { + QGCTool::setToolbox(toolbox); + qmlRegisterType(_factSystemQmlUri, 1, 0, "Fact"); + qmlRegisterType(_factSystemQmlUri, 1, 0, "FactPanelController"); } diff --git a/src/FactSystem/FactSystem.h b/src/FactSystem/FactSystem.h index 9708010cad253d242acf5bbd0597f59b010ce240..c752a2821f113792b92676b229c6e3b6cec86508 100644 --- a/src/FactSystem/FactSystem.h +++ b/src/FactSystem/FactSystem.h @@ -29,10 +29,8 @@ #include "Fact.h" #include "FactMetaData.h" -#include "QGCSingleton.h" +#include "QGCToolbox.h" -/// FactSystem is a singleton which provides access to the Facts in the system -/// /// The components of the FactSystem are a Fact which holds an individual value. FactMetaData holds /// additional meta data associated with a Fact such as description, min/max ranges and so forth. /// The FactValidator object is a QML validator which validates input according to the FactMetaData @@ -40,13 +38,17 @@ /// of this is the PX4ParameterMetaData onbject which is part of the PX4 AutoPilot plugin. It exposes /// the firmware parameters to QML such that you can bind QML ui elements directly to parameters. -class FactSystem : public QGCSingleton +class FactSystem : public QGCTool { Q_OBJECT - DECLARE_QGC_SINGLETON(FactSystem, FactSystem) - public: + /// All access to FactSystem is through FactSystem::instance, so constructor is private + FactSystem(QGCApplication* app); + + // Override from QGCTool + virtual void setToolbox(QGCToolbox *toolbox); + typedef enum { ParameterProvider, } Provider_t; @@ -54,10 +56,6 @@ public: static const int defaultComponentId = -1; private: - /// All access to FactSystem is through FactSystem::instance, so constructor is private - FactSystem(QObject* parent = NULL); - ~FactSystem(); - static const char* _factSystemQmlUri; ///< URI for FactSystem QML imports }; diff --git a/src/FactSystem/FactSystemTestBase.cc b/src/FactSystem/FactSystemTestBase.cc index cc1b1b2ab57afa660e57825279db38d1e1c3bc0a..67c759e352b4ee1bf1f0d2e1e3fa03f076b731ef 100644 --- a/src/FactSystem/FactSystemTestBase.cc +++ b/src/FactSystem/FactSystemTestBase.cc @@ -44,19 +44,9 @@ void FactSystemTestBase::_init(MAV_AUTOPILOT autopilot) { UnitTest::init(); - MockLink* link = new MockLink(); - link->setFirmwareType(autopilot); - LinkManager::instance()->_addLink(link); + _connectMockLink(autopilot); - LinkManager::instance()->connectLink(link); - - // Wait for the Vehicle to get created - QSignalSpy spyVehicle(MultiVehicleManager::instance(), SIGNAL(parameterReadyVehicleAvailableChanged(bool))); - QCOMPARE(spyVehicle.wait(5000), true); - QVERIFY(MultiVehicleManager::instance()->parameterReadyVehicleAvailable()); - QVERIFY(MultiVehicleManager::instance()->activeVehicle()); - - _plugin = MultiVehicleManager::instance()->activeVehicle()->autopilotPlugin(); + _plugin = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->autopilotPlugin(); Q_ASSERT(_plugin); } diff --git a/src/FactSystem/ParameterLoader.cc b/src/FactSystem/ParameterLoader.cc index 0f77589b55dacf2f20a25b24809e232caf717c3b..81b07f758f8a5e84482c6d4ba44287820baf50d6 100644 --- a/src/FactSystem/ParameterLoader.cc +++ b/src/FactSystem/ParameterLoader.cc @@ -50,7 +50,7 @@ ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, Q QObject(parent), _autopilot(autopilot), _vehicle(vehicle), - _mavlink(MAVLinkProtocol::instance()), + _mavlink(qgcApp()->toolbox()->mavlinkProtocol()), _parametersReady(false), _initialLoadComplete(false), _defaultComponentId(FactSystem::defaultComponentId), @@ -308,7 +308,7 @@ void ParameterLoader::refreshAllParameters(void) _dataMutex.unlock(); - MAVLinkProtocol* mavlink = MAVLinkProtocol::instance(); + MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); Q_ASSERT(mavlink); mavlink_message_t msg; @@ -501,7 +501,7 @@ void ParameterLoader::_tryCacheLookup() /* Start waiting for 2.5 seconds to get a cache hit and avoid loading all params over the radio */ _cacheTimeoutTimer.start(); - MAVLinkProtocol* mavlink = MAVLinkProtocol::instance(); + MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); Q_ASSERT(mavlink); mavlink_message_t msg; @@ -825,7 +825,7 @@ void ParameterLoader::_checkInitialLoadComplete(void) // Check for any errors during vehicle boot - UASMessageHandler* msgHandler = UASMessageHandler::instance(); + UASMessageHandler* msgHandler = qgcApp()->toolbox()->uasMessageHandler(); if (msgHandler->getErrorCountTotal()) { QString errors; bool firstError = true; diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 46a44aeeca762508dc3fafd8d8580fe06576e3e0..7eec705ce56665485ae2cfa49f54a14f7bea82f9 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -139,8 +139,7 @@ QString APMCustomMode::modeString() const return mode; } -APMFirmwarePlugin::APMFirmwarePlugin(QObject* parent) - : FirmwarePlugin(parent) +APMFirmwarePlugin::APMFirmwarePlugin(void) { _textSeverityAdjustmentNeeded = false; } diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h index bc5fe1f664371705c0bcfc4e00f6f082610a173e..d1c429ca1c9a5d02172b01f371f4ecc1f5d7a1c5 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h @@ -94,7 +94,7 @@ public: protected: /// All access to singleton is through stack specific implementation - APMFirmwarePlugin(QObject* parent = NULL); + APMFirmwarePlugin(void); void setSupportedModes(QList supportedModes); private: diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc index 5d4a972dfb378ce985b425126224e5b9448c3ff0..1cb1cdc77d1484307483bdf334e578eea3b13b19 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc @@ -53,8 +53,7 @@ APMCopterMode::APMCopterMode(uint32_t mode, bool settable) : APMCustomMode(mode, setEnumToStringMapping(enumToString); } -ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(QObject* parent) : - APMFirmwarePlugin(parent) +ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void) { QList supportedFlightModes; supportedFlightModes << APMCopterMode(APMCopterMode::STABILIZE ,true); diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h index a94e820101a4b87506cd07ae7364f13508ca92d4..62a70c54247b68dcb948de0a29fd079a1ae1c1fe 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h @@ -68,7 +68,7 @@ public: protected: /// All access to singleton is through instance() - ArduCopterFirmwarePlugin(QObject* parent = NULL); + ArduCopterFirmwarePlugin(void); private: }; diff --git a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc index e4de1ac62628a8d41cde8252d3f833457b83efdc..ea6eaed674222aef9438fe6f514c3e8d72a896a4 100644 --- a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc @@ -50,8 +50,7 @@ APMPlaneMode::APMPlaneMode(uint32_t mode, bool settable) : APMCustomMode(mode, s setEnumToStringMapping(enumToString); } -ArduPlaneFirmwarePlugin::ArduPlaneFirmwarePlugin(QObject* parent) : - APMFirmwarePlugin(parent) +ArduPlaneFirmwarePlugin::ArduPlaneFirmwarePlugin(void) { QList supportedFlightModes; supportedFlightModes << APMPlaneMode(APMPlaneMode::MANUAL ,true); diff --git a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h index 648f19b9f73ab4ba1877aee5176eb55251d7577c..84913452e38b1eae1909e62ff5b2fca61b3e0ec1 100644 --- a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h @@ -66,7 +66,7 @@ public: protected: /// All access to singleton is through instance() - ArduPlaneFirmwarePlugin(QObject* parent = NULL); + ArduPlaneFirmwarePlugin(void); private: }; diff --git a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc index 2488a2a4a7a0f72d07a676c2e200eaf9bbc608e8..d620714d75acd969a9c3bdfc75453a36ef01ada2 100644 --- a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc @@ -44,8 +44,7 @@ APMRoverMode::APMRoverMode(uint32_t mode, bool settable) : APMCustomMode(mode, s setEnumToStringMapping(enumToString); } -ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(QObject* parent) : - APMFirmwarePlugin(parent) +ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(void) { QList supportedFlightModes; supportedFlightModes << APMRoverMode(APMRoverMode::MANUAL ,true); diff --git a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h index 697a2466ca4e20899ef18dd55d84d9c9fe6f941b..b50971cb8d0fa2803812128be44345ead8ae273e 100644 --- a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h @@ -66,7 +66,7 @@ public: protected: /// All access to singleton is through instance() - ArduRoverFirmwarePlugin(QObject* parent = NULL); + ArduRoverFirmwarePlugin(void); private: }; diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index 6e389c835fbd7ee7065313e5ac42baac9f22767b..df226d9f431fb7bd22e0c8b7deec14aa25bb5b02 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -112,7 +112,7 @@ public: virtual void addMetaDataToFact(Fact* fact) = 0; protected: - FirmwarePlugin(QObject* parent = NULL) : QGCSingleton(parent) { } + FirmwarePlugin(void) { }; }; #endif diff --git a/src/FirmwarePlugin/FirmwarePluginManager.cc b/src/FirmwarePlugin/FirmwarePluginManager.cc index a781f0bf8853150c2c0d65ec3d2ed0b866eadb9d..aec991eaa3792d5f59cd769c12e87c9bff25b725 100644 --- a/src/FirmwarePlugin/FirmwarePluginManager.cc +++ b/src/FirmwarePlugin/FirmwarePluginManager.cc @@ -31,19 +31,6 @@ #include "APM/ArduRoverFirmwarePlugin.h" #include "PX4/PX4FirmwarePlugin.h" -IMPLEMENT_QGC_SINGLETON(FirmwarePluginManager, FirmwarePluginManager) - -FirmwarePluginManager::FirmwarePluginManager(QObject* parent) : - QGCSingleton(parent) -{ - -} - -FirmwarePluginManager::~FirmwarePluginManager() -{ - -} - FirmwarePlugin* FirmwarePluginManager::firmwarePluginForAutopilot(MAV_AUTOPILOT autopilotType, MAV_TYPE vehicleType) { switch (autopilotType) { diff --git a/src/FirmwarePlugin/FirmwarePluginManager.h b/src/FirmwarePlugin/FirmwarePluginManager.h index 1d415354595d92e07dc8f6fd548ea786b4668713..84f32ca95c86bf22410e402cc80b32afa1c27568 100644 --- a/src/FirmwarePlugin/FirmwarePluginManager.h +++ b/src/FirmwarePlugin/FirmwarePluginManager.h @@ -29,29 +29,26 @@ #include -#include "QGCSingleton.h" #include "FirmwarePlugin.h" #include "QGCMAVLink.h" +#include "QGCToolbox.h" + +class QGCApplication; /// FirmwarePluginManager is a singleton which is used to return the correct FirmwarePlugin for a MAV_AUTOPILOT type. -class FirmwarePluginManager : public QGCSingleton +class FirmwarePluginManager : public QGCTool { Q_OBJECT - - DECLARE_QGC_SINGLETON(FirmwarePluginManager, FirmwarePluginManager) public: + FirmwarePluginManager(QGCApplication* app) : QGCTool(app) { } + /// Returns appropriate plugin for autopilot type. /// @param autopilotType Type of autopilot to return plugin for. /// @param vehicleType Vehicle type of autopilot to return plugin for. /// @return Singleton FirmwarePlugin instance for the specified MAV_AUTOPILOT. FirmwarePlugin* firmwarePluginForAutopilot(MAV_AUTOPILOT autopilotType, MAV_TYPE vehicleType); - -private: - /// All access to singleton is through FirmwarePluginManager::instance - FirmwarePluginManager(QObject* parent = NULL); - ~FirmwarePluginManager(); }; #endif diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc index 9d62a42d1f714b2867d6c3b541ba5030d113a93e..a14c949c56a48d8d8364f24816c5171611bf467f 100644 --- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc +++ b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc @@ -31,8 +31,7 @@ IMPLEMENT_QGC_SINGLETON(GenericFirmwarePlugin, FirmwarePlugin) -GenericFirmwarePlugin::GenericFirmwarePlugin(QObject* parent) - : FirmwarePlugin(parent) +GenericFirmwarePlugin::GenericFirmwarePlugin(void) { } diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h index d488332eb968fa28a1a93fc97717dcff37308273..6d6f210415d72a8567efcc248086f567618cb8ba 100644 --- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h +++ b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h @@ -51,8 +51,7 @@ public: virtual QString getDefaultComponentIdParam(void) const { return QString(); } private: - /// All access to singleton is through AutoPilotPluginManager::instance - GenericFirmwarePlugin(QObject* parent = NULL); + GenericFirmwarePlugin(void); }; #endif diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index 77da20de535df55e9a002db5a1944396beffdb2f..44277c03c0c3fea75d0ddf122aa2488c3bf5a316 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -88,8 +88,7 @@ static const struct Modes2Name rgModes2Name[] = { }; -PX4FirmwarePlugin::PX4FirmwarePlugin(QObject* parent) - : FirmwarePlugin(parent) +PX4FirmwarePlugin::PX4FirmwarePlugin(void) { } diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h index 73063286f9f89cb90e2451c5b3166281f771edc6..0c67ef4594f3138b8f9b4fa6803210eb4569bfb9 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h @@ -53,7 +53,7 @@ public: private: /// All access to singleton is through AutoPilotPluginManager::instance - PX4FirmwarePlugin(QObject* parent = NULL); + PX4FirmwarePlugin(void); PX4ParameterMetaData _parameterMetaData; }; diff --git a/src/FlightMap/FlightMapSettings.cc b/src/FlightMap/FlightMapSettings.cc index 5d2b33f4ea5de6527d01137f06d282790cc5562f..63fa846f810ad0390d9cb407a887a8839e13a114 100644 --- a/src/FlightMap/FlightMapSettings.cc +++ b/src/FlightMap/FlightMapSettings.cc @@ -26,27 +26,26 @@ #include #include -IMPLEMENT_QGC_SINGLETON(FlightMapSettings, FlightMapSettings) - const char* FlightMapSettings::_defaultMapProvider = "Bing"; // Bing is default since it support full street/satellite/hybrid set const char* FlightMapSettings::_settingsGroup = "FlightMapSettings"; const char* FlightMapSettings::_mapProviderKey = "MapProvider"; const char* FlightMapSettings::_mapTypeKey = "MapType"; -FlightMapSettings::FlightMapSettings(QObject* parent) - : QObject(parent) +FlightMapSettings::FlightMapSettings(QGCApplication* app) + : QGCTool(app) , _mapProvider(_defaultMapProvider) { - qmlRegisterUncreatableType ("QGroundControl", 1, 0, "FlightMapSetting", "Reference only"); - - _supportedMapProviders << "Bing" << "Google" << "Open"; - - _loadSettings(); } -FlightMapSettings::~FlightMapSettings() +void FlightMapSettings::setToolbox(QGCToolbox *toolbox) { + QGCTool::setToolbox(toolbox); + qmlRegisterUncreatableType ("QGroundControl", 1, 0, "FlightMapSetting", "Reference only"); + + _supportedMapProviders << "Bing" << "Google" << "Open"; + + _loadSettings(); } void FlightMapSettings::_storeSettings(void) diff --git a/src/FlightMap/FlightMapSettings.h b/src/FlightMap/FlightMapSettings.h index 375e68c6430496722950d5cf19c2234db5760811..28590dab763ba4b2d81d9a25d98119bebadff61b 100644 --- a/src/FlightMap/FlightMapSettings.h +++ b/src/FlightMap/FlightMapSettings.h @@ -24,17 +24,18 @@ This file is part of the QGROUNDCONTROL project #ifndef FlightMapSettings_H #define FlightMapSettings_H -#include "QGCSingleton.h" +#include "QGCToolbox.h" +#include #include -class FlightMapSettings : public QObject +class FlightMapSettings : public QGCTool { Q_OBJECT - DECLARE_QGC_SINGLETON(FlightMapSettings, FlightMapSettings) - public: + FlightMapSettings(QGCApplication* app); + /// mapProvider is either Bing, Google or Open to specify to set of maps available Q_PROPERTY(QString mapProvider READ mapProvider WRITE setMapProvider NOTIFY mapProviderChanged) @@ -54,15 +55,14 @@ public: QString mapProvider(void); void setMapProvider(const QString& mapProvider); + // Override from QGCTool + virtual void setToolbox(QGCToolbox *toolbox); + signals: void mapProviderChanged(const QString& mapProvider); void mapTypesChanged(const QStringList& mapTypes); private: - /// @brief All access to FlightMapSettings singleton is through FlightMapSettings::instance - FlightMapSettings(QObject* parent = NULL); - ~FlightMapSettings(); - void _storeSettings(void); void _loadSettings(void); diff --git a/src/GAudioOutput.cc b/src/GAudioOutput.cc index 743e44c0fd84135576a96853c4d5820247d17253..e8804f9fd82dc2099b04c42f70e973c2b4fb6321 100644 --- a/src/GAudioOutput.cc +++ b/src/GAudioOutput.cc @@ -43,12 +43,10 @@ This file is part of the QGROUNDCONTROL project #include #endif -IMPLEMENT_QGC_SINGLETON(GAudioOutput, GAudioOutput) - const char* GAudioOutput::_mutedKey = "AudioMuted"; -GAudioOutput::GAudioOutput(QObject *parent) - : QGCSingleton(parent) +GAudioOutput::GAudioOutput(QGCApplication* app) + : QGCTool(app) , muted(false) #ifndef __android__ , thread(new QThread()) @@ -57,7 +55,7 @@ GAudioOutput::GAudioOutput(QObject *parent) { QSettings settings; muted = settings.value(_mutedKey, false).toBool(); - muted |= qgcApp()->runningUnitTests(); + muted |= app->runningUnitTests(); #ifndef __android__ worker->moveToThread(thread); connect(this, &GAudioOutput::textToSpeak, worker, &QGCAudioWorker::say); diff --git a/src/GAudioOutput.h b/src/GAudioOutput.h index 3e0f8d84483bb19b6928c279d64e5af043b5cc94..c121c6826df8b67952104f302371aec8b04ae05d 100644 --- a/src/GAudioOutput.h +++ b/src/GAudioOutput.h @@ -38,20 +38,23 @@ This file is part of the PIXHAWK project #include #include "QGCAudioWorker.h" -#include "QGCSingleton.h" +#include "QGCToolbox.h" + +class QGCApplication; /** * @brief Audio Output (speech synthesizer and "beep" output) * This class follows the singleton design pattern * @see http://en.wikipedia.org/wiki/Singleton_pattern */ -class GAudioOutput : public QGCSingleton +class GAudioOutput : public QGCTool { Q_OBJECT - DECLARE_QGC_SINGLETON(GAudioOutput, GAudioOutput) - public: + GAudioOutput(QGCApplication* app); + ~GAudioOutput(); + /** @brief List available voices */ QStringList listVoices(void); enum @@ -95,9 +98,6 @@ protected: #endif private: - GAudioOutput(QObject *parent = NULL); - ~GAudioOutput(); - static const char* _mutedKey; }; diff --git a/src/HomePositionManager.cc b/src/HomePositionManager.cc index 5c07db78c234ec23200cf78e5c8163c38483be03..14b06ba1b72d5006dc64174f37657c3a1d8cf079 100644 --- a/src/HomePositionManager.cc +++ b/src/HomePositionManager.cc @@ -39,27 +39,27 @@ #define MEAN_EARTH_DIAMETER 12756274.0 #define UMR 0.017453292519943295769236907684886 -IMPLEMENT_QGC_SINGLETON(HomePositionManager, HomePositionManager) - const char* HomePositionManager::_settingsGroup = "HomePositionManager"; const char* HomePositionManager::_latitudeKey = "Latitude"; const char* HomePositionManager::_longitudeKey = "Longitude"; const char* HomePositionManager::_altitudeKey = "Altitude"; -HomePositionManager::HomePositionManager(QObject* parent) - : QObject(parent) +HomePositionManager::HomePositionManager(QGCApplication* app) + : QGCTool(app) , homeLat(47.3769) , homeLon(8.549444) , homeAlt(470.0) { - qmlRegisterUncreatableType ("QGroundControl", 1, 0, "HomePositionManager", "Reference only"); - - _loadSettings(); + } -HomePositionManager::~HomePositionManager() +void HomePositionManager::setToolbox(QGCToolbox *toolbox) { + QGCTool::setToolbox(toolbox); + + qmlRegisterUncreatableType ("QGroundControl", 1, 0, "HomePositionManager", "Reference only"); + _loadSettings(); } void HomePositionManager::_storeSettings(void) @@ -116,7 +116,7 @@ void HomePositionManager::_loadSettings(void) settings.endGroup(); if (_homePositions.count() == 0) { - _homePositions.append(new HomePosition("ETH Campus", QGeoCoordinate(47.3769, 8.549444, 470.0))); + _homePositions.append(new HomePosition("ETH Campus", QGeoCoordinate(47.3769, 8.549444, 470.0), this)); } // Deprecated settings for old editor @@ -169,7 +169,7 @@ bool HomePositionManager::setHomePositionAndNotify(double lat, double lon, doubl bool changed = setHomePosition(lat, lon, alt); if (changed) { - MultiVehicleManager::instance()->setHomePositionForAllVehicles(homeLat, homeLon, homeAlt); + qgcApp()->toolbox()->multiVehicleManager()->setHomePositionForAllVehicles(homeLat, homeLon, homeAlt); } return changed; @@ -218,9 +218,10 @@ void HomePositionManager::deleteHomePosition(const QString& name) _storeSettings(); } -HomePosition::HomePosition(const QString& name, const QGeoCoordinate& coordinate, QObject* parent) +HomePosition::HomePosition(const QString& name, const QGeoCoordinate& coordinate, HomePositionManager* homePositionManager, QObject* parent) : QObject(parent) , _coordinate(coordinate) + , _homePositionManager(homePositionManager) { setObjectName(name); } @@ -238,7 +239,7 @@ QString HomePosition::name(void) void HomePosition::setName(const QString& name) { setObjectName(name); - HomePositionManager::instance()->_storeSettings(); + _homePositionManager->_storeSettings(); emit nameChanged(name); } @@ -250,6 +251,6 @@ QGeoCoordinate HomePosition::coordinate(void) void HomePosition::setCoordinate(const QGeoCoordinate& coordinate) { _coordinate = coordinate; - HomePositionManager::instance()->_storeSettings(); + _homePositionManager->_storeSettings(); emit coordinateChanged(coordinate); } diff --git a/src/HomePositionManager.h b/src/HomePositionManager.h index 0d34024d01b8ae49a03a676466497a97f02e3cc7..0b3d2d5e42b1bf04aabafe4fe51b18ed5591d548 100644 --- a/src/HomePositionManager.h +++ b/src/HomePositionManager.h @@ -24,17 +24,19 @@ This file is part of the QGROUNDCONTROL project #ifndef HomePositionManager_H #define HomePositionManager_H -#include "QGCSingleton.h" #include "QmlObjectListModel.h" +#include "QGCToolbox.h" #include +class HomePositionManager; + class HomePosition : public QObject { Q_OBJECT public: - HomePosition(const QString& name, const QGeoCoordinate& coordinate, QObject* parent = NULL); + HomePosition(const QString& name, const QGeoCoordinate& coordinate, HomePositionManager* homePositionManager, QObject* parent = NULL); ~HomePosition(); Q_PROPERTY(QString name READ name WRITE setName NOTIFY nameChanged) @@ -47,22 +49,23 @@ public: QGeoCoordinate coordinate(void); void setCoordinate(const QGeoCoordinate& coordinate); - + signals: void nameChanged(const QString& name); void coordinateChanged(const QGeoCoordinate& coordinate); private: - QGeoCoordinate _coordinate; + QGeoCoordinate _coordinate; + HomePositionManager* _homePositionManager; }; -class HomePositionManager : public QObject +class HomePositionManager : public QGCTool { Q_OBJECT - DECLARE_QGC_SINGLETON(HomePositionManager, HomePositionManager) - public: + HomePositionManager(QGCApplication* app); + Q_PROPERTY(QmlObjectListModel* homePositions READ homePositions CONSTANT) /// If name is not already a home position a new one will be added, otherwise the existing @@ -78,14 +81,13 @@ public: // Should only be called by HomePosition void _storeSettings(void); + // Override from QGCTool + virtual void setToolbox(QGCToolbox *toolbox); + private: - /// @brief All access to HomePositionManager singleton is through HomePositionManager::instance - HomePositionManager(QObject* parent = NULL); - ~HomePositionManager(); - void _loadSettings(void); - QmlObjectListModel _homePositions; + QmlObjectListModel _homePositions; static const char* _settingsGroup; static const char* _latitudeKey; diff --git a/src/Joystick/Joystick.cc b/src/Joystick/Joystick.cc index 6e7e377382a92fee895c42fe0afefacebf0b3339..e35eaf0257785b694f3c9b1ce985c4791d8478c3 100644 --- a/src/Joystick/Joystick.cc +++ b/src/Joystick/Joystick.cc @@ -23,7 +23,6 @@ #include "Joystick.h" #include "QGC.h" -#include "MultiVehicleManager.h" #include "AutoPilotPlugin.h" #include "UAS.h" @@ -52,7 +51,7 @@ const char* Joystick::_rgFunctionSettingsKey[Joystick::maxFunction] = { "ThrottleAxis" }; -Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int sdlIndex) +Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int sdlIndex, MultiVehicleManager* multiVehicleManager) #ifndef __mobile__ : _sdlIndex(sdlIndex) , _exitThread(false) @@ -68,6 +67,7 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int sdlI , _throttleMode(ThrottleModeCenterZero) , _activeVehicle(NULL) , _pollingStartedForCalibration(false) + , _multiVehicleManager(multiVehicleManager) #endif // __mobile__ { #ifdef __mobile__ @@ -520,7 +520,7 @@ void Joystick::startCalibrationMode(CalibrationMode_t mode) if (!isRunning()) { _pollingStartedForCalibration = true; - startPolling(MultiVehicleManager::instance()->activeVehicle()); + startPolling(_multiVehicleManager->activeVehicle()); } } diff --git a/src/Joystick/Joystick.h b/src/Joystick/Joystick.h index db125b4c70beaf49c417a9c90672c079119bf462..c26752ff81cc50c9566c08cdceb9e400b53625b2 100644 --- a/src/Joystick/Joystick.h +++ b/src/Joystick/Joystick.h @@ -29,6 +29,7 @@ #include "QGCLoggingCategory.h" #include "Vehicle.h" +#include "MultiVehicleManager.h" Q_DECLARE_LOGGING_CATEGORY(JoystickLog) Q_DECLARE_LOGGING_CATEGORY(JoystickValuesLog) @@ -38,7 +39,7 @@ class Joystick : public QThread Q_OBJECT public: - Joystick(const QString& name, int axisCount, int buttonCount, int sdlIndex); + Joystick(const QString& name, int axisCount, int buttonCount, int sdlIndex, MultiVehicleManager* multiVehicleManager); ~Joystick(); typedef struct { @@ -171,6 +172,8 @@ private: Vehicle* _activeVehicle; bool _pollingStartedForCalibration; + + MultiVehicleManager* _multiVehicleManager; #endif // __mobile__ private: diff --git a/src/Joystick/JoystickManager.cc b/src/Joystick/JoystickManager.cc index d45bec4814034a03a0b72653c3259244591887dc..40487a34f133fa60e8fa0e8412f6b1d422374edc 100644 --- a/src/Joystick/JoystickManager.cc +++ b/src/Joystick/JoystickManager.cc @@ -22,6 +22,7 @@ ======================================================================*/ #include "JoystickManager.h" +#include "QGCApplication.h" #include @@ -35,58 +36,62 @@ QGC_LOGGING_CATEGORY(JoystickManagerLog, "JoystickManagerLog") -IMPLEMENT_QGC_SINGLETON(JoystickManager, JoystickManager) - const char * JoystickManager::_settingsGroup = "JoystickManager"; const char * JoystickManager::_settingsKeyActiveJoystick = "ActiveJoystick"; -JoystickManager::JoystickManager(QObject* parent) - : QGCSingleton(parent) +JoystickManager::JoystickManager(QGCApplication* app) + : QGCTool(app) , _activeJoystick(NULL) + , _multiVehicleManager(NULL) { - QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); +} + +void JoystickManager::setToolbox(QGCToolbox *toolbox) +{ + QGCTool::setToolbox(toolbox); + + _multiVehicleManager = _toolbox->multiVehicleManager(); + + QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); + #ifndef __mobile__ if (SDL_InitSubSystem(SDL_INIT_JOYSTICK | SDL_INIT_NOPARACHUTE) < 0) { qWarning() << "Couldn't initialize SimpleDirectMediaLayer:" << SDL_GetError(); return; } - + // Load available joysticks - + qCDebug(JoystickManagerLog) << "Available joysticks"; - + for (int i=0; i Q_DECLARE_LOGGING_CATEGORY(JoystickManagerLog) -class JoystickManager : public QGCSingleton +class QGCApplicaiton; + +class JoystickManager : public QGCTool { Q_OBJECT - DECLARE_QGC_SINGLETON(JoystickManager, JoystickManager) - public: + JoystickManager(QGCApplication* app); + /// List of available joysticks Q_PROPERTY(QVariantList joysticks READ joysticks CONSTANT) Q_PROPERTY(QStringList joystickNames READ joystickNames CONSTANT) @@ -56,6 +59,9 @@ public: QString activeJoystickName(void); void setActiveJoystickName(const QString& name); + // Override from QGCTool + virtual void setToolbox(QGCToolbox *toolbox); + signals: void activeJoystickChanged(Joystick* joystick); void activeJoystickNameChanged(const QString& name); @@ -63,16 +69,12 @@ signals: private slots: private: - /// All access to singleton is through JoystickManager::instance - JoystickManager(QObject* parent = NULL); - ~JoystickManager(); - void _setActiveJoystickFromSettings(void); private: - Joystick* _activeJoystick; - + Joystick* _activeJoystick; QMap _name2JoystickMap; + MultiVehicleManager* _multiVehicleManager; static const char * _settingsGroup; static const char * _settingsKeyActiveJoystick; diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 35f60c92bd3176962c4d7cfd29677563e9dc7485..bd4188152704d6324b3c73c5906b7109dbbc4549 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -62,7 +62,7 @@ void MissionController::start(bool editMode) _editMode = editMode; - MultiVehicleManager* multiVehicleMgr = MultiVehicleManager::instance(); + MultiVehicleManager* multiVehicleMgr = qgcApp()->toolbox()->multiVehicleManager(); connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionController::_activeVehicleChanged); @@ -143,7 +143,7 @@ void MissionController::_setupMissionItems(bool loadFromVehicle, bool forceLoad) void MissionController::getMissionItems(void) { - Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle(); + Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle(); if (activeVehicle) { _missionItemsRequested = true; @@ -153,7 +153,7 @@ void MissionController::getMissionItems(void) void MissionController::sendMissionItems(void) { - Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle(); + Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle(); if (activeVehicle) { activeVehicle->missionManager()->writeMissionItems(*_missionItems); @@ -576,7 +576,7 @@ void MissionController::setAutoSync(bool autoSync) void MissionController::_dirtyChanged(bool dirty) { if (dirty && _autoSync) { - Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle(); + Vehicle* activeVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle(); if (activeVehicle && !activeVehicle->armed()) { if (_activeVehicle->missionManager()->inProgress()) { diff --git a/src/MissionManager/MissionControllerManagerTest.cc b/src/MissionManager/MissionControllerManagerTest.cc index 55e97a30a7a2c4f2a7de98e6fec701ce648f36d7..4618e0700ad42632a20923ef5b56a4d5b4cc52ac 100644 --- a/src/MissionManager/MissionControllerManagerTest.cc +++ b/src/MissionManager/MissionControllerManagerTest.cc @@ -24,9 +24,9 @@ #include "MissionControllerManagerTest.h" #include "LinkManager.h" #include "MultiVehicleManager.h" +#include "QGCApplication.h" MissionControllerManagerTest::MissionControllerManagerTest(void) - : _mockLink(NULL) { } @@ -36,33 +36,16 @@ void MissionControllerManagerTest::cleanup(void) delete _multiSpyMissionManager; _multiSpyMissionManager = NULL; - LinkManager::instance()->disconnectLink(_mockLink); - _mockLink = NULL; - QTest::qWait(1000); // Need to allow signals to move between threads - UnitTest::cleanup(); } void MissionControllerManagerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType) { - LinkManager* linkMgr = LinkManager::instance(); - Q_CHECK_PTR(linkMgr); - - _mockLink = new MockLink(); - Q_CHECK_PTR(_mockLink); - _mockLink->setFirmwareType(firmwareType); - LinkManager::instance()->_addLink(_mockLink); - - linkMgr->connectLink(_mockLink); - - // Wait for the Vehicle to work it's way through the various threads - - QSignalSpy spyVehicle(MultiVehicleManager::instance(), SIGNAL(activeVehicleChanged(Vehicle*))); - QCOMPARE(spyVehicle.wait(5000), true); + _connectMockLink(firmwareType); // Wait for the Mission Manager to finish it's initial load - _missionManager = MultiVehicleManager::instance()->activeVehicle()->missionManager(); + _missionManager = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->missionManager(); QVERIFY(_missionManager); _rgMissionManagerSignals[canEditChangedSignalIndex] = SIGNAL(canEditChanged(bool)); diff --git a/src/MissionManager/MissionControllerManagerTest.h b/src/MissionManager/MissionControllerManagerTest.h index 4c62bd741e517adc514bf256ad41be65cf5e7170..32230873c8cfab6087bcb620841cd73cbb78b821 100644 --- a/src/MissionManager/MissionControllerManagerTest.h +++ b/src/MissionManager/MissionControllerManagerTest.h @@ -46,7 +46,6 @@ protected: void _initForFirmwareType(MAV_AUTOPILOT firmwareType); void _checkInProgressValues(bool inProgress); - MockLink* _mockLink; MissionManager* _missionManager; typedef struct { diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc index ccb6af749f55bb66ae26a621d16b6abec22e046c..a9af8316c564fbed80c26f1a30d89f4837c066a5 100644 --- a/src/MissionManager/MissionManager.cc +++ b/src/MissionManager/MissionManager.cc @@ -28,6 +28,7 @@ #include "Vehicle.h" #include "FirmwarePlugin.h" #include "MAVLinkProtocol.h" +#include "QGCApplication.h" QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog") @@ -92,7 +93,7 @@ void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems) missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER; missionCount.count = _missionItems.count(); - mavlink_msg_mission_count_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &missionCount); + mavlink_msg_mission_count_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &missionCount); _vehicle->sendMessage(message); _startAckTimeout(AckMissionRequest); @@ -112,7 +113,7 @@ void MissionManager::_retryWrite(void) missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER; missionCount.count = _missionItems.count(); - mavlink_msg_mission_count_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &missionCount); + mavlink_msg_mission_count_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &missionCount); _vehicle->sendMessage(message); _startAckTimeout(AckMissionRequest); @@ -131,7 +132,7 @@ void MissionManager::requestMissionItems(void) request.target_system = _vehicle->id(); request.target_component = MAV_COMP_ID_MISSIONPLANNER; - mavlink_msg_mission_request_list_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &request); + mavlink_msg_mission_request_list_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &request); _vehicle->sendMessage(message); _startAckTimeout(AckMissionCount); @@ -150,7 +151,7 @@ void MissionManager::_retryRead(void) request.target_system = _vehicle->id(); request.target_component = MAV_COMP_ID_MISSIONPLANNER; - mavlink_msg_mission_request_list_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &request); + mavlink_msg_mission_request_list_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &request); _vehicle->sendMessage(message); _startAckTimeout(AckMissionCount); @@ -214,7 +215,7 @@ void MissionManager::_readTransactionComplete(void) missionAck.target_component = MAV_COMP_ID_MISSIONPLANNER; missionAck.type = MAV_MISSION_ACCEPTED; - mavlink_msg_mission_ack_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &missionAck); + mavlink_msg_mission_ack_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &missionAck); _vehicle->sendMessage(message); @@ -260,7 +261,7 @@ void MissionManager::_requestNextMissionItem(int sequenceNumber) missionRequest.seq = sequenceNumber; _expectedSequenceNumber = sequenceNumber; - mavlink_msg_mission_request_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &message, &missionRequest); + mavlink_msg_mission_request_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &missionRequest); _vehicle->sendMessage(message); _startAckTimeout(AckMissionItem); @@ -361,7 +362,7 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message) missionItem.current = missionRequest.seq == 0; missionItem.autocontinue = item->autoContinue(); - mavlink_msg_mission_item_encode(MAVLinkProtocol::instance()->getSystemId(), MAVLinkProtocol::instance()->getComponentId(), &messageOut, &missionItem); + mavlink_msg_mission_item_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &messageOut, &missionItem); _vehicle->sendMessage(messageOut); _startAckTimeout(AckMissionRequest); diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index 29ec286fa9a74cbe2e3b6d256652deaaf5bc1c26..beca8faabde96f4dabcc04b6b471604374daac4f 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -137,7 +137,7 @@ static QObject* mavlinkQmlSingletonFactory(QQmlEngine*, QJSEngine*) static QObject* qgroundcontrolQmlGlobalSingletonFactory(QQmlEngine*, QJSEngine*) { - return new QGroundControlQmlGlobal; + return new QGroundControlQmlGlobal(qgcApp()->toolbox()); } #if defined(QGC_GST_STREAMING) @@ -172,6 +172,7 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) #ifdef QT_DEBUG , _testHighDPI(false) #endif + , _toolbox(NULL) { Q_ASSERT(_app == NULL); _app = this; @@ -315,12 +316,15 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) // Initialize Video Streaming initializeVideoStreaming(argc, argv); + + _toolbox = new QGCToolbox(this); } QGCApplication::~QGCApplication() { _destroySingletons(); shutdownVideoStreaming(); + delete _toolbox; } void QGCApplication::_initCommon(void) @@ -458,12 +462,12 @@ bool QGCApplication::_initForNormalAppBoot(void) #ifndef __mobile__ // Now that main window is up check for lost log files - connect(this, &QGCApplication::checkForLostLogFiles, MAVLinkProtocol::instance(), &MAVLinkProtocol::checkForLostLogFiles); + connect(this, &QGCApplication::checkForLostLogFiles, toolbox()->mavlinkProtocol(), &MAVLinkProtocol::checkForLostLogFiles); emit checkForLostLogFiles(); #endif // Load known link configurations - LinkManager::instance()->loadLinkConfigurationList(); + toolbox()->linkManager()->loadLinkConfigurationList(); return true; } @@ -574,18 +578,6 @@ QGCApplication* qgcApp(void) /// up being creating on something other than the main thread. void QGCApplication::_createSingletons(void) { - // The order here is important since the singletons reference each other - - // No dependencies - FlightMapSettings* flightMapSettings = FlightMapSettings::_createSingleton(); - Q_UNUSED(flightMapSettings); - Q_ASSERT(flightMapSettings); - - // No dependencies - HomePositionManager* homePositionManager = HomePositionManager::_createSingleton(); - Q_UNUSED(homePositionManager); - Q_ASSERT(homePositionManager); - // No dependencies FirmwarePlugin* firmwarePlugin = GenericFirmwarePlugin::_createSingleton(); Q_UNUSED(firmwarePlugin); @@ -596,52 +588,6 @@ void QGCApplication::_createSingletons(void) firmwarePlugin = ArduCopterFirmwarePlugin::_createSingleton(); firmwarePlugin = ArduPlaneFirmwarePlugin::_createSingleton(); firmwarePlugin = ArduRoverFirmwarePlugin::_createSingleton(); - - // No dependencies - FirmwarePluginManager* firmwarePluginManager = FirmwarePluginManager::_createSingleton(); - Q_UNUSED(firmwarePluginManager); - Q_ASSERT(firmwarePluginManager); - - // No dependencies - MultiVehicleManager* multiVehicleManager = MultiVehicleManager::_createSingleton(); - Q_UNUSED(multiVehicleManager); - Q_ASSERT(multiVehicleManager); - - // No dependencies - JoystickManager* joystickManager = JoystickManager::_createSingleton(); - Q_UNUSED(joystickManager); - Q_ASSERT(joystickManager); - - // No dependencies - GAudioOutput* audio = GAudioOutput::_createSingleton(); - Q_UNUSED(audio); - Q_ASSERT(audio); - - // No dependencies - LinkManager* linkManager = LinkManager::_createSingleton(); - Q_UNUSED(linkManager); - Q_ASSERT(linkManager); - - // Need MultiVehicleManager - AutoPilotPluginManager* pluginManager = AutoPilotPluginManager::_createSingleton(); - Q_UNUSED(pluginManager); - Q_ASSERT(pluginManager); - - // Need MultiVehicleManager - UASMessageHandler* messageHandler = UASMessageHandler::_createSingleton(); - Q_UNUSED(messageHandler); - Q_ASSERT(messageHandler); - - // Needs MultiVehicleManager - FactSystem* factSystem = FactSystem::_createSingleton(); - Q_UNUSED(factSystem); - Q_ASSERT(factSystem); - - // Needs everything! - MAVLinkProtocol* mavlink = MAVLinkProtocol::_createSingleton(); - Q_UNUSED(mavlink); - Q_ASSERT(mavlink); - } void QGCApplication::_destroySingletons(void) @@ -651,32 +597,11 @@ void QGCApplication::_destroySingletons(void) delete mainWindow; } - if (LinkManager::instance(true /* nullOk */)) { - // This will close/delete all connections - LinkManager::instance()->_shutdown(); - } - - // Let the signals flow through the main thread - processEvents(QEventLoop::ExcludeUserInputEvents); - - // Take down singletons in reverse order of creation - - MAVLinkProtocol::_deleteSingleton(); - FactSystem::_deleteSingleton(); - UASMessageHandler::_deleteSingleton(); - AutoPilotPluginManager::_deleteSingleton(); - LinkManager::_deleteSingleton(); - GAudioOutput::_deleteSingleton(); - JoystickManager::_deleteSingleton(); - MultiVehicleManager::_deleteSingleton(); - FirmwarePluginManager::_deleteSingleton(); GenericFirmwarePlugin::_deleteSingleton(); PX4FirmwarePlugin::_deleteSingleton(); ArduCopterFirmwarePlugin::_deleteSingleton(); ArduPlaneFirmwarePlugin::_deleteSingleton(); ArduRoverFirmwarePlugin::_deleteSingleton(); - HomePositionManager::_deleteSingleton(); - FlightMapSettings::_deleteSingleton(); } void QGCApplication::informationMessageBoxOnMainThread(const QString& title, const QString& msg) diff --git a/src/QGCApplication.h b/src/QGCApplication.h index f503a7f915ce5a87c4f549f947c2db8dc9c565f8..08fb609cfadefa33c0a7fc6b6e5add5706dc7de2 100644 --- a/src/QGCApplication.h +++ b/src/QGCApplication.h @@ -36,6 +36,17 @@ #include #include "LinkConfiguration.h" +#include "LinkManager.h" +#include "MAVLinkProtocol.h" +#include "FlightMapSettings.h" +#include "HomePositionManager.h" +#include "FirmwarePluginManager.h" +#include "MultiVehicleManager.h" +#include "JoystickManager.h" +#include "GAudioOutput.h" +#include "AutoPilotPluginManager.h" +#include "UASMessageHandler.h" +#include "FactSystem.h" #ifdef QGC_RTLAB_ENABLED #include "OpalLink.h" @@ -44,6 +55,7 @@ // Work around circular header includes class QGCSingleton; class MainWindow; +class QGCToolbox; /** * @brief The main application and management class. @@ -109,6 +121,9 @@ public: #ifdef QT_DEBUG bool testHighDPI(void) { return _testHighDPI; } #endif + + // Still working on getting rid of this and using dependency injection instead for everything + QGCToolbox* toolbox(void) { return _toolbox; } public slots: /// You can connect to this slot to show an information message box from a different thread. @@ -122,7 +137,7 @@ public slots: /// Save the specified Flight Data Log void saveTempFlightDataLogOnMainThread(QString tempLogfile); - + signals: /// Signals that the style has changed /// @param darkStyle true: dark style, false: light style @@ -166,7 +181,7 @@ private: static const char* _defaultSavedFileDirectoryName; ///< Default name for user visible save file directory static const char* _savedFileMavlinkLogDirectoryName; ///< Name of mavlink log subdirectory static const char* _savedFileParameterDirectoryName; ///< Name of parameter subdirectory - + bool _runningUnitTests; ///< true: running unit tests, false: normal app static const char* _darkStyleFile; @@ -183,6 +198,8 @@ private: bool _testHighDPI; ///< true: double fonts sizes for simulating high dpi devices #endif + QGCToolbox* _toolbox; + /// Unit Test have access to creating and destroying singletons friend class UnitTest; }; diff --git a/src/QGCQuickWidget.cc b/src/QGCQuickWidget.cc index 351d48177fb715306477cfd1109e15c583824cb2..db7a4cf4c2782df0624fcf9a58fd7c1933f0d3a7 100644 --- a/src/QGCQuickWidget.cc +++ b/src/QGCQuickWidget.cc @@ -40,8 +40,8 @@ QGCQuickWidget::QGCQuickWidget(QWidget* parent) : QQuickWidget(parent) { rootContext()->engine()->addImportPath("qrc:/qml"); - rootContext()->setContextProperty("multiVehicleManager", MultiVehicleManager::instance()); - rootContext()->setContextProperty("joystickManager", JoystickManager::instance()); + rootContext()->setContextProperty("multiVehicleManager", qgcApp()->toolbox()->multiVehicleManager()); + rootContext()->setContextProperty("joystickManager", qgcApp()->toolbox()->joystickManager()); } void QGCQuickWidget::setAutoPilot(AutoPilotPlugin* autoPilot) diff --git a/src/QGCSingleton.cc b/src/QGCSingleton.cc index 3149523f417c2368c2e459ecb23004999451e068..24da38cdfbf1da8ebb17d7b74d770af44f48c586 100644 --- a/src/QGCSingleton.cc +++ b/src/QGCSingleton.cc @@ -29,8 +29,3 @@ #include "QGCSingleton.h" #include "QGCApplication.h" -QGCSingleton::QGCSingleton(QObject* parent) : - QObject(parent) -{ - -} diff --git a/src/QGCSingleton.h b/src/QGCSingleton.h index 3b07d2f7dfe3ff1d866a60b8b23d311b019df2fd..2f4ea01ff5abc754cb051142c953a93fccfb78d4 100644 --- a/src/QGCSingleton.h +++ b/src/QGCSingleton.h @@ -27,8 +27,6 @@ #ifndef QGCSINGLETON_H #define QGCSINGLETON_H -#include "QGCApplication.h" - #include #include @@ -40,14 +38,12 @@ public: \ static interfaceName* instance(bool nullOk = false); \ static void setMockInstance(interfaceName* mock); \ - private: \ static interfaceName* _createSingleton(void); \ static void _deleteSingleton(void); \ + private: \ static interfaceName* _instance; \ static interfaceName* _mockInstance; \ static interfaceName* _realInstance; \ - friend class QGCApplication; \ - friend class UnitTest; \ /// @def IMPLEMENT_QGC_SINGLETON /// Include this macro in your Derived Class implementation @@ -61,7 +57,7 @@ interfaceName* className::_createSingleton(void) \ { \ Q_ASSERT(_instance == NULL); \ - _instance = new className(qgcApp()); \ + _instance = new className; \ return _instance; \ } \ \ @@ -151,10 +147,6 @@ class QGCSingleton : public QObject { Q_OBJECT -protected: - /// Constructor is private since all creation is done through _createInstance - /// @param parent Parent object - QGCSingleton(QObject* parent = NULL); }; #endif diff --git a/src/QGCToolbox.cc b/src/QGCToolbox.cc new file mode 100644 index 0000000000000000000000000000000000000000..659a21755260b50c820b46cddab3712aeb8f622d --- /dev/null +++ b/src/QGCToolbox.cc @@ -0,0 +1,100 @@ + /*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009 - 2015 QGROUNDCONTROL PROJECT + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + + ======================================================================*/ + +#include "LinkManager.h" +#include "MAVLinkProtocol.h" +#include "FlightMapSettings.h" +#include "HomePositionManager.h" +#include "FirmwarePluginManager.h" +#include "MultiVehicleManager.h" +#include "JoystickManager.h" +#include "GAudioOutput.h" +#include "AutoPilotPluginManager.h" +#include "UASMessageHandler.h" +#include "FactSystem.h" + +QGCToolbox::QGCToolbox(QGCApplication* app) + : _firmwarePluginManager(NULL) + , _autopilotPluginManager(NULL) + , _linkManager(NULL) + , _multiVehicleManager(NULL) + , _mavlinkProtocol(NULL) + , _flightMapSettings(NULL) + , _homePositionManager(NULL) + , _joystickManager(NULL) + , _audioOutput(NULL) + , _uasMessageHandler(NULL) + , _factSystem(NULL) +{ + _firmwarePluginManager = new FirmwarePluginManager(app); + _autopilotPluginManager = new AutoPilotPluginManager(app); + _flightMapSettings = new FlightMapSettings(app); + _homePositionManager = new HomePositionManager(app); + _factSystem = new FactSystem(app); + _linkManager = new LinkManager(app); + _multiVehicleManager = new MultiVehicleManager(app); + _mavlinkProtocol = new MAVLinkProtocol(app); + _joystickManager = new JoystickManager(app); + _audioOutput = new GAudioOutput(app); + _uasMessageHandler = new UASMessageHandler(app); + + _firmwarePluginManager->setToolbox(this); + _autopilotPluginManager->setToolbox(this); + _flightMapSettings->setToolbox(this); + _homePositionManager->setToolbox(this); + _factSystem->setToolbox(this); + _linkManager->setToolbox(this); + _multiVehicleManager->setToolbox(this); + _mavlinkProtocol->setToolbox(this); + _joystickManager->setToolbox(this); + _audioOutput->setToolbox(this); + _uasMessageHandler->setToolbox(this); +} + +QGCToolbox::~QGCToolbox() +{ + delete _firmwarePluginManager; + delete _autopilotPluginManager; + delete _linkManager; + delete _multiVehicleManager; + delete _mavlinkProtocol; + delete _flightMapSettings; + delete _homePositionManager; + delete _joystickManager; + delete _audioOutput; + delete _uasMessageHandler; + delete _factSystem; +} + +QGCTool::QGCTool(QGCApplication* app) + : QObject((QObject*)app) + , _app(app) + , _toolbox(NULL) +{ + +} + +void QGCTool::setToolbox(QGCToolbox* toolbox) +{ + _toolbox = toolbox; +} diff --git a/src/QGCToolbox.h b/src/QGCToolbox.h new file mode 100644 index 0000000000000000000000000000000000000000..79ef8d715f261f5404cbb374b8cdeecdae896b9c --- /dev/null +++ b/src/QGCToolbox.h @@ -0,0 +1,91 @@ +/*===================================================================== + + QGroundControl Open Source Ground Control Station + + (c) 2009 - 2015 QGROUNDCONTROL PROJECT + + This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + + ======================================================================*/ + +#ifndef QGCToolbox_h +#define QGCToolbox_h + +#include + +class QGCApplication; +class LinkManager; +class MAVLinkProtocol; +class MultiVehicleManager; +class JoystickManager; +class UASMessageHandler; +class HomePositionManager; +class FlightMapSettings; +class GAudioOutput; +class FirmwarePluginManager; +class AutoPilotPluginManager; +class FactSystem; + +/// This is used to manage all of our top level services/tools +class QGCToolbox { + +public: + QGCToolbox(QGCApplication* app); + ~QGCToolbox(); + + LinkManager* linkManager(void) { return _linkManager; } + MAVLinkProtocol* mavlinkProtocol(void) { return _mavlinkProtocol; } + MultiVehicleManager* multiVehicleManager(void) { return _multiVehicleManager; } + JoystickManager* joystickManager(void) { return _joystickManager; } + UASMessageHandler* uasMessageHandler(void) { return _uasMessageHandler; } + HomePositionManager* homePositionManager(void) { return _homePositionManager; } + FlightMapSettings* flightMapSettings(void) { return _flightMapSettings; } + GAudioOutput* audioOutput(void) { return _audioOutput; } + FirmwarePluginManager* firmwarePluginManager(void) { return _firmwarePluginManager; } + AutoPilotPluginManager* autopilotPluginManager(void) { return _autopilotPluginManager; } + +private: + FirmwarePluginManager* _firmwarePluginManager; + AutoPilotPluginManager* _autopilotPluginManager; + LinkManager* _linkManager; + MultiVehicleManager* _multiVehicleManager; + MAVLinkProtocol* _mavlinkProtocol; + FlightMapSettings* _flightMapSettings; + HomePositionManager* _homePositionManager; + JoystickManager* _joystickManager; + GAudioOutput* _audioOutput; + UASMessageHandler* _uasMessageHandler; + FactSystem* _factSystem; +}; + +/// This is the base class for all tools +class QGCTool : public QObject { + Q_OBJECT + +public: + // All tools are parented to QGCAppliation and go through a two phase creation. First all tools are newed, + // and then setToolbox is called on all tools. The prevents creating an circular dependencies at constructor + // time. + QGCTool(QGCApplication* app); + + virtual void setToolbox(QGCToolbox* toolbox); + +protected: + QGCApplication* _app; + QGCToolbox* _toolbox; +}; + +#endif diff --git a/src/QmlControls/ParameterEditorController.cc b/src/QmlControls/ParameterEditorController.cc index bf6eb4871b40d3a893f92d18e186d8794d23044a..4818152ce282c2fa0bf806d299f4cc7b47731ee7 100644 --- a/src/QmlControls/ParameterEditorController.cc +++ b/src/QmlControls/ParameterEditorController.cc @@ -158,6 +158,6 @@ void ParameterEditorController::resetAllToDefaults(void) void ParameterEditorController::setRCToParam(const QString& paramName) { Q_ASSERT(_uas); - QGCMapRCToParamDialog * d = new QGCMapRCToParamDialog(paramName, _uas, MainWindow::instance()); + QGCMapRCToParamDialog * d = new QGCMapRCToParamDialog(paramName, _uas, qgcApp()->toolbox()->multiVehicleManager(), MainWindow::instance()); d->exec(); } diff --git a/src/QmlControls/QGroundControlQmlGlobal.cc b/src/QmlControls/QGroundControlQmlGlobal.cc index a9f26fb1ab2a6c5f39f73276f901205b6a6343ee..53dd03924c2d99b3e53424d94864a4f5b9ea2843 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.cc +++ b/src/QmlControls/QGroundControlQmlGlobal.cc @@ -25,18 +25,16 @@ /// @author Don Gagne #include "QGroundControlQmlGlobal.h" +#include "QGCApplication.h" + +#include static const char* kQmlGlobalKeyName = "QGCQml"; -QGroundControlQmlGlobal::QGroundControlQmlGlobal(QObject* parent) +QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCToolbox* toolbox, QObject* parent) : QObject(parent) - , _homePositionManager(HomePositionManager::instance()) - , _flightMapSettings(FlightMapSettings::instance()) -{ - -} - -QGroundControlQmlGlobal::~QGroundControlQmlGlobal() + , _homePositionManager(toolbox->homePositionManager()) + , _flightMapSettings(toolbox->flightMapSettings()) { } diff --git a/src/QmlControls/QGroundControlQmlGlobal.h b/src/QmlControls/QGroundControlQmlGlobal.h index 52655212a3162a206f1a824ef6488336bcfb1659..506a93f91fb2b3dd014bbed9f9e2a82d2b871389 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.h +++ b/src/QmlControls/QGroundControlQmlGlobal.h @@ -32,13 +32,14 @@ #include "HomePositionManager.h" #include "FlightMapSettings.h" +class QGCToolbox; + class QGroundControlQmlGlobal : public QObject { Q_OBJECT public: - QGroundControlQmlGlobal(QObject* parent = NULL); - ~QGroundControlQmlGlobal(); + QGroundControlQmlGlobal(QGCToolbox* toolbox, QObject* parent = NULL); Q_PROPERTY(HomePositionManager* homePositionManager READ homePositionManager CONSTANT) Q_PROPERTY(FlightMapSettings* flightMapSettings READ flightMapSettings CONSTANT) diff --git a/src/Vehicle/MultiVehicleManager.cc b/src/Vehicle/MultiVehicleManager.cc index 708e67b98a542b2424e7da81334362a5368e7e34..026edc8247526c41c2eb97332697cbc595d0afb0 100644 --- a/src/Vehicle/MultiVehicleManager.cc +++ b/src/Vehicle/MultiVehicleManager.cc @@ -28,42 +28,52 @@ #include "AutoPilotPlugin.h" #include "MAVLinkProtocol.h" #include "UAS.h" +#include "QGCApplication.h" -IMPLEMENT_QGC_SINGLETON(MultiVehicleManager, MultiVehicleManager) - -MultiVehicleManager::MultiVehicleManager(QObject* parent) : - QGCSingleton(parent) +MultiVehicleManager::MultiVehicleManager(QGCApplication* app) + : QGCTool(app) , _activeVehicleAvailable(false) , _parameterReadyVehicleAvailable(false) , _activeVehicle(NULL) + , _firmwarePluginManager(NULL) + , _autopilotPluginManager(NULL) + , _joystickManager(NULL) + , _mavlinkProtocol(NULL) { - QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); - qmlRegisterUncreatableType("QGroundControl.MultiVehicleManager", 1, 0, "MultiVehicleManager", "Reference only"); + } -MultiVehicleManager::~MultiVehicleManager() +void MultiVehicleManager::setToolbox(QGCToolbox *toolbox) { + QGCTool::setToolbox(toolbox); + + _firmwarePluginManager = _toolbox->firmwarePluginManager(); + _autopilotPluginManager = _toolbox->autopilotPluginManager(); + _joystickManager = _toolbox->joystickManager(); + _mavlinkProtocol = _toolbox->mavlinkProtocol(); + QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); + qmlRegisterUncreatableType("QGroundControl.MultiVehicleManager", 1, 0, "MultiVehicleManager", "Reference only"); } bool MultiVehicleManager::notifyHeartbeatInfo(LinkInterface* link, int vehicleId, mavlink_heartbeat_t& heartbeat) { if (!getVehicleById(vehicleId) && !_ignoreVehicleIds.contains(vehicleId)) { - if (vehicleId == MAVLinkProtocol::instance()->getSystemId()) { - qgcApp()->showToolBarMessage(QString("Warning: A vehicle is using the same system id as QGroundControl: %1").arg(vehicleId)); + if (vehicleId == _mavlinkProtocol->getSystemId()) { + _app->showToolBarMessage(QString("Warning: A vehicle is using the same system id as QGroundControl: %1").arg(vehicleId)); } QSettings settings; bool mavlinkVersionCheck = settings.value("VERSION_CHECK_ENABLED", true).toBool(); if (mavlinkVersionCheck && heartbeat.mavlink_version != MAVLINK_VERSION) { _ignoreVehicleIds += vehicleId; - qgcApp()->showToolBarMessage(QString("The MAVLink protocol version on vehicle #%1 and QGroundControl differ! " + _app->showToolBarMessage(QString("The MAVLink protocol version on vehicle #%1 and QGroundControl differ! " "It is unsafe to use different MAVLink versions. " "QGroundControl therefore refuses to connect to vehicle #%1, which sends MAVLink version %2 (QGroundControl uses version %3).").arg(vehicleId).arg(heartbeat.mavlink_version).arg(MAVLINK_VERSION)); return false; } - Vehicle* vehicle = new Vehicle(link, vehicleId, (MAV_AUTOPILOT)heartbeat.autopilot, (MAV_TYPE)heartbeat.type); + Vehicle* vehicle = new Vehicle(link, vehicleId, (MAV_AUTOPILOT)heartbeat.autopilot, (MAV_TYPE)heartbeat.type, _firmwarePluginManager, _autopilotPluginManager, _joystickManager); if (!vehicle) { qWarning() << "New Vehicle allocation failed"; diff --git a/src/Vehicle/MultiVehicleManager.h b/src/Vehicle/MultiVehicleManager.h index 36a717129fcfe511d312a18e3465b5eae7011079..badc782ca9171e6c08c9a1872da06168e361cec9 100644 --- a/src/Vehicle/MultiVehicleManager.h +++ b/src/Vehicle/MultiVehicleManager.h @@ -27,18 +27,24 @@ #ifndef MultiVehicleManager_H #define MultiVehicleManager_H -#include "QGCSingleton.h" #include "Vehicle.h" #include "QGCMAVLink.h" #include "QmlObjectListModel.h" +#include "QGCToolbox.h" -class MultiVehicleManager : public QGCSingleton +class FirmwarePluginManager; +class AutoPilotPluginManager; +class JoystickManager; +class QGCApplication; +class MAVLinkProtocol; + +class MultiVehicleManager : public QGCTool { Q_OBJECT - DECLARE_QGC_SINGLETON(MultiVehicleManager, MultiVehicleManager) - public: + MultiVehicleManager(QGCApplication* app); + Q_INVOKABLE void saveSetting (const QString &key, const QString& value); Q_INVOKABLE QString loadSetting (const QString &key, const QString& defaultValue); @@ -76,6 +82,9 @@ public: QmlObjectListModel* vehiclesModel(void) { return &_vehicles; } + // Override from QGCTool + virtual void setToolbox(QGCToolbox *toolbox); + signals: void vehicleAdded(Vehicle* vehicle); void vehicleRemoved(Vehicle* vehicle); @@ -92,10 +101,6 @@ private slots: void _autopilotParametersReadyChanged(bool parametersReady); private: - /// All access to singleton is through MultiVehicleManager::instance - MultiVehicleManager(QObject* parent = NULL); - ~MultiVehicleManager(); - bool _vehicleExists(int vehicleId); bool _activeVehicleAvailable; ///< true: An active vehicle is available @@ -108,6 +113,11 @@ private: QList _ignoreVehicleIds; ///< List of vehicle id for which we ignore further communication QmlObjectListModel _vehicles; + + FirmwarePluginManager* _firmwarePluginManager; + AutoPilotPluginManager* _autopilotPluginManager; + JoystickManager* _joystickManager; + MAVLinkProtocol* _mavlinkProtocol; }; #endif diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 4b38181bf701bd2f5328ccd6a2054378d82cd02a..f83189622c95101a5ac07091c44f2ab70de14911 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -33,6 +33,7 @@ #include "MissionManager.h" #include "CoordinateVector.h" #include "ParameterLoader.h" +#include "QGCApplication.h" QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog") @@ -45,7 +46,13 @@ const char* Vehicle::_joystickModeSettingsKey = "JoystickMode"; const char* Vehicle::_joystickEnabledSettingsKey = "JoystickEnabled"; const char* Vehicle::_communicationInactivityKey = "CommunicationInactivity"; -Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType) +Vehicle::Vehicle(LinkInterface* link, + int vehicleId, + MAV_AUTOPILOT firmwareType, + MAV_TYPE vehicleType, + FirmwarePluginManager* firmwarePluginManager, + AutoPilotPluginManager* autopilotPluginManager, + JoystickManager* joystickManager) : _id(vehicleId) , _active(false) , _firmwareType(firmwareType) @@ -96,15 +103,18 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType, , _custom_mode(0) , _nextSendMessageMultipleIndex(0) , _communicationInactivityTimeoutMSecs(_communicationInactivityTimeoutMSecsDefault) + , _firmwarePluginManager(firmwarePluginManager) + , _autopilotPluginManager(autopilotPluginManager) + , _joystickManager(joystickManager) { _addLink(link); - _mavlink = MAVLinkProtocol::instance(); + _mavlink = qgcApp()->toolbox()->mavlinkProtocol(); connect(_mavlink, &MAVLinkProtocol::messageReceived, this, &Vehicle::_mavlinkMessageReceived); connect(this, &Vehicle::_sendMessageOnThread, this, &Vehicle::_sendMessage, Qt::QueuedConnection); - _uas = new UAS(_mavlink, this); + _uas = new UAS(_mavlink, this, _firmwarePluginManager); setLatitude(_uas->getLatitude()); setLongitude(_uas->getLongitude()); @@ -112,8 +122,8 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType, connect(_uas, &UAS::latitudeChanged, this, &Vehicle::setLatitude); connect(_uas, &UAS::longitudeChanged, this, &Vehicle::setLongitude); - _firmwarePlugin = FirmwarePluginManager::instance()->firmwarePluginForAutopilot(_firmwareType, _vehicleType); - _autopilotPlugin = AutoPilotPluginManager::instance()->newAutopilotPluginForVehicle(this); + _firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType); + _autopilotPlugin = _autopilotPluginManager->newAutopilotPluginForVehicle(this); connect(_autopilotPlugin, &AutoPilotPlugin::parametersReadyChanged, this, &Vehicle::_parametersReady); connect(_autopilotPlugin, &AutoPilotPlugin::missingParametersChanged, this, &Vehicle::missingParametersChanged); @@ -132,7 +142,7 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType, _currentHeartbeatTimeout = 0; emit heartbeatTimeoutChanged(); // Listen for system messages - connect(UASMessageHandler::instance(), &UASMessageHandler::textMessageCountChanged, this, &Vehicle::_handleTextMessage); + connect(qgcApp()->toolbox()->uasMessageHandler(), &UASMessageHandler::textMessageCountChanged, this, &Vehicle::_handleTextMessage); // Now connect the new UAS connect(_mav, SIGNAL(attitudeChanged (UASInterface*,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*, double, double, double, quint64))); connect(_mav, SIGNAL(attitudeChanged (UASInterface*,int,double,double,double,quint64)), this, SLOT(_updateAttitude(UASInterface*,int,double, double, double, quint64))); @@ -178,9 +188,14 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType, Vehicle::~Vehicle() { + qDebug() << "~Vehicle"; + delete _missionManager; _missionManager = NULL; + delete _autopilotPlugin; + _autopilotPlugin = NULL; + delete _mav; _mav = NULL; } @@ -285,9 +300,9 @@ bool Vehicle::_containsLink(LinkInterface* link) void Vehicle::_addLink(LinkInterface* link) { if (!_containsLink(link)) { - _links += LinkManager::instance()->sharedPointerForLink(link); + _links += qgcApp()->toolbox()->linkManager()->sharedPointerForLink(link); qCDebug(VehicleLog) << "_addLink:" << QString("%1").arg((ulong)link, 0, 16); - connect(LinkManager::instance(), &LinkManager::linkDisconnected, this, &Vehicle::_linkDisconnected); + connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkDisconnected, this, &Vehicle::_linkDisconnected); } } @@ -790,7 +805,7 @@ void Vehicle::_handleTextMessage(int newCount) return; } - UASMessageHandler* pMh = UASMessageHandler::instance(); + UASMessageHandler* pMh = qgcApp()->toolbox()->uasMessageHandler(); Q_ASSERT(pMh); MessageType_t type = newCount ? _currentMessageType : MessageNone; int errorCount = _currentErrorCount; @@ -941,7 +956,7 @@ void Vehicle::setJoystickEnabled(bool enabled) void Vehicle::_startJoystick(bool start) { #ifndef __mobile__ - Joystick* joystick = JoystickManager::instance()->activeJoystick(); + Joystick* joystick = _joystickManager->activeJoystick(); if (joystick) { if (start) { if (_joystickEnabled) { @@ -1149,7 +1164,7 @@ void Vehicle::_communicationInactivityTimedOut(void) { // Vechile is no longer communicating with us, disconnect all links - LinkManager* linkMgr = LinkManager::instance(); + LinkManager* linkMgr = qgcApp()->toolbox()->linkManager(); for (int i=0; i<_links.count(); i++) { linkMgr->disconnectLink(_links[i].data()); } diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index eb0666f855993eda19c91a11caf11cb8c339e922..0a0e833064a549d3e8bf64e4308ae36747faca0c 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -40,9 +40,12 @@ class UAS; class UASInterface; class FirmwarePlugin; +class FirmwarePluginManager; class AutoPilotPlugin; +class AutoPilotPluginManager; class MissionManager; class ParameterLoader; +class JoystickManager; Q_DECLARE_LOGGING_CATEGORY(VehicleLog) @@ -51,7 +54,13 @@ class Vehicle : public QObject Q_OBJECT public: - Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType); + Vehicle(LinkInterface* link, + int vehicleId, + MAV_AUTOPILOT firmwareType, + MAV_TYPE vehicleType, + FirmwarePluginManager* firmwarePluginManager, + AutoPilotPluginManager* autopilotPluginManager, + JoystickManager* joystickManager); ~Vehicle(); Q_PROPERTY(int id READ id CONSTANT) @@ -444,6 +453,10 @@ private: QTimer _communicationInactivityTimer; int _communicationInactivityTimeoutMSecs; static const int _communicationInactivityTimeoutMSecsDefault = 30 * 1000; + + FirmwarePluginManager* _firmwarePluginManager; + AutoPilotPluginManager* _autopilotPluginManager; + JoystickManager* _joystickManager; // Settings keys static const char* _settingsGroup; diff --git a/src/VehicleSetup/FirmwareUpgradeController.cc b/src/VehicleSetup/FirmwareUpgradeController.cc index 7085ef29c8c14a90267d3ee34f1d88df7963bf31..9019f58a3a42729b44997062f4e42d42f6a8577a 100644 --- a/src/VehicleSetup/FirmwareUpgradeController.cc +++ b/src/VehicleSetup/FirmwareUpgradeController.cc @@ -68,7 +68,7 @@ FirmwareUpgradeController::FirmwareUpgradeController(void) : connect(_threadController, &PX4FirmwareUpgradeThreadController::flashComplete, this, &FirmwareUpgradeController::_flashComplete); connect(_threadController, &PX4FirmwareUpgradeThreadController::updateProgress, this, &FirmwareUpgradeController::_updateProgress); - connect(LinkManager::instance(), &LinkManager::linkDisconnected, this, &FirmwareUpgradeController::_linkDisconnected); + connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkDisconnected, this, &FirmwareUpgradeController::_linkDisconnected); connect(&_eraseTimer, &QTimer::timeout, this, &FirmwareUpgradeController::_eraseProgressTick); } @@ -558,7 +558,7 @@ void FirmwareUpgradeController::_appendStatusLog(const QString& text, bool criti bool FirmwareUpgradeController::qgcConnections(void) { - return LinkManager::instance()->anyConnectedLinks(); + return qgcApp()->toolbox()->linkManager()->anyConnectedLinks(); } void FirmwareUpgradeController::_linkDisconnected(LinkInterface* link) diff --git a/src/VehicleSetup/JoystickConfigController.cc b/src/VehicleSetup/JoystickConfigController.cc index bede44e95a492b4b6c37cb598a86eb0bc521253e..f6003e6f5188394beb66fad8dccc4c3a3f3a6dce 100644 --- a/src/VehicleSetup/JoystickConfigController.cc +++ b/src/VehicleSetup/JoystickConfigController.cc @@ -24,6 +24,7 @@ #include "JoystickConfigController.h" #include "JoystickManager.h" #include "QGCMessageBox.h" +#include "QGCApplication.h" #include @@ -66,12 +67,12 @@ JoystickConfigController::JoystickConfigController(void) , _cancelButton(NULL) , _nextButton(NULL) , _skipButton(NULL) + , _joystickManager(qgcApp()->toolbox()->joystickManager()) { - JoystickManager* joystickManager = JoystickManager::instance(); - connect(joystickManager, &JoystickManager::activeJoystickChanged, this, &JoystickConfigController::_activeJoystickChanged); + connect(_joystickManager, &JoystickManager::activeJoystickChanged, this, &JoystickConfigController::_activeJoystickChanged); - _activeJoystickChanged(joystickManager->activeJoystick()); + _activeJoystickChanged(_joystickManager->activeJoystick()); _resetInternalCalibrationValues(); } @@ -454,7 +455,7 @@ void JoystickConfigController::_resetInternalCalibrationValues(void) /// @brief Sets internal calibration values from the stored settings void JoystickConfigController::_setInternalCalibrationValuesFromSettings(void) { - Joystick* joystick = JoystickManager::instance()->activeJoystick(); + Joystick* joystick = _joystickManager->activeJoystick(); // Initialize all function mappings to not set @@ -539,7 +540,7 @@ void JoystickConfigController::_validateCalibration(void) /// @brief Saves the rc calibration values to the board parameters. void JoystickConfigController::_writeCalibration(void) { - Joystick* joystick = JoystickManager::instance()->activeJoystick(); + Joystick* joystick = _joystickManager->activeJoystick(); _validateCalibration(); diff --git a/src/VehicleSetup/JoystickConfigController.h b/src/VehicleSetup/JoystickConfigController.h index faada23997ec4e7fca7c35eabc9694ed8e7dd07c..8555e0792dfd61150fcd8814597964f9e026964c 100644 --- a/src/VehicleSetup/JoystickConfigController.h +++ b/src/VehicleSetup/JoystickConfigController.h @@ -38,6 +38,7 @@ Q_DECLARE_LOGGING_CATEGORY(JoystickConfigControllerLog) class RadioConfigest; +class JoystickManager; namespace Ui { class JoystickConfigController; @@ -253,6 +254,8 @@ private: QQuickItem* _skipButton; QString _imageHelp; + + JoystickManager* _joystickManager; }; #endif // JoystickConfigController_H diff --git a/src/VehicleSetup/SetupViewTest.cc b/src/VehicleSetup/SetupViewTest.cc index 3891dc4e6013fd64456ffd963b2740faec711c13..11d29ba9efd2e02205160063adcb47c960a88816 100644 --- a/src/VehicleSetup/SetupViewTest.cc +++ b/src/VehicleSetup/SetupViewTest.cc @@ -31,50 +31,14 @@ UT_REGISTER_TEST(SetupViewTest) -SetupViewTest::SetupViewTest(void) : - _mainWindow(NULL) -{ - -} - -void SetupViewTest::init(void) -{ - UnitTest::init(); - - _mainWindow = MainWindow::_create(); - Q_CHECK_PTR(_mainWindow); -} - -void SetupViewTest::cleanup(void) -{ - _mainWindow->close(); - delete _mainWindow; - - UnitTest::cleanup(); -} - void SetupViewTest::_clickThrough_test(void) { - LinkManager* linkMgr = LinkManager::instance(); - Q_CHECK_PTR(linkMgr); + _connectMockLink(); - MockLink* link = new MockLink(); - Q_CHECK_PTR(link); - link->setFirmwareType(MAV_AUTOPILOT_PX4); - LinkManager::instance()->_addLink(link); - linkMgr->connectLink(link); - - // Wait for the Vehicle to get created - QSignalSpy spyVehicle(MultiVehicleManager::instance(), SIGNAL(parameterReadyVehicleAvailableChanged(bool))); - QCOMPARE(spyVehicle.wait(5000), true); - QVERIFY(MultiVehicleManager::instance()->parameterReadyVehicleAvailable()); - QVERIFY(MultiVehicleManager::instance()->activeVehicle()); - - AutoPilotPlugin* autopilot = MultiVehicleManager::instance()->activeVehicle()->autopilotPlugin(); + AutoPilotPlugin* autopilot = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->autopilotPlugin(); Q_ASSERT(autopilot); - - MainWindow* mainWindow = MainWindow::instance(); - Q_ASSERT(mainWindow); + + _createMainWindow(); // Switch to the Setup view _mainWindow->showSetupView(); @@ -103,7 +67,6 @@ void SetupViewTest::_clickThrough_test(void) setExpectedMessageBox(QGCMessageBox::Yes); - _mainWindow->close(); - QTest::qWait(1000); // Need to allow signals to move between threads + _closeMainWindow(); checkExpectedMessageBox(); } diff --git a/src/VehicleSetup/SetupViewTest.h b/src/VehicleSetup/SetupViewTest.h index 134fc212d9bf5c7ab0626c1614cc8accc3163541..bd1802d90b5bab9cb70be11c34727cf751dff3a0 100644 --- a/src/VehicleSetup/SetupViewTest.h +++ b/src/VehicleSetup/SetupViewTest.h @@ -35,17 +35,8 @@ class SetupViewTest : public UnitTest { Q_OBJECT -public: - SetupViewTest(void); - private slots: - void init(void); - void cleanup(void); - void _clickThrough_test(void); - -private: - MainWindow* _mainWindow; }; #endif diff --git a/src/ViewWidgets/CustomCommandWidgetController.cc b/src/ViewWidgets/CustomCommandWidgetController.cc index 80c482cff01a11262ed9d596c6f6d7e36b70a341..24e1a06f10f9b76308769846b2f38101c8ac45c5 100644 --- a/src/ViewWidgets/CustomCommandWidgetController.cc +++ b/src/ViewWidgets/CustomCommandWidgetController.cc @@ -26,6 +26,7 @@ #include "QGCMAVLink.h" #include "QGCFileDialog.h" #include "UAS.h" +#include "QGCApplication.h" #include #include @@ -35,7 +36,7 @@ const char* CustomCommandWidgetController::_settingsKey = "CustomCommand.QmlFile CustomCommandWidgetController::CustomCommandWidgetController(void) : _uas(NULL) { - _uas = MultiVehicleManager::instance()->activeVehicle()->uas(); + _uas = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->uas(); Q_ASSERT(_uas); QSettings settings; diff --git a/src/ViewWidgets/ViewWidgetController.cc b/src/ViewWidgets/ViewWidgetController.cc index 5a39032d669b9e9e4f353e4b5d739719533d6172..a6636110b5d8d423d34923d8dc76ad834d6f5dc9 100644 --- a/src/ViewWidgets/ViewWidgetController.cc +++ b/src/ViewWidgets/ViewWidgetController.cc @@ -24,12 +24,13 @@ #include "ViewWidgetController.h" #include "MultiVehicleManager.h" #include "UAS.h" +#include "QGCApplication.h" ViewWidgetController::ViewWidgetController(void) : _autopilot(NULL), _uas(NULL) { - connect(MultiVehicleManager::instance(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &ViewWidgetController::_vehicleAvailable); + connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &ViewWidgetController::_vehicleAvailable); } void ViewWidgetController::_vehicleAvailable(bool available) @@ -41,7 +42,7 @@ void ViewWidgetController::_vehicleAvailable(bool available) } if (available) { - Vehicle* vehicle = MultiVehicleManager::instance()->activeVehicle(); + Vehicle* vehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle(); _uas = vehicle->uas(); _autopilot = vehicle->autopilotPlugin(); @@ -51,5 +52,5 @@ void ViewWidgetController::_vehicleAvailable(bool available) } Q_INVOKABLE void ViewWidgetController::checkForVehicle(void) { - _vehicleAvailable(MultiVehicleManager::instance()->activeVehicle()); + _vehicleAvailable(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()); } diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc index 967d1ff7553cbaad1d4906bf9a93cd22350b02c4..0378b62b5d22ded9eaba33109ea3675f966fb3d0 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -46,27 +46,20 @@ This file is part of the QGROUNDCONTROL project #include "QGCMessageBox.h" #include "QGCApplication.h" #include "SerialPortIds.h" +#include "QGCApplication.h" -IMPLEMENT_QGC_SINGLETON(LinkManager, LinkManager) QGC_LOGGING_CATEGORY(LinkManagerLog, "LinkManagerLog") -/** - * @brief Private singleton constructor - * - * This class implements the singleton design pattern and has therefore only a private constructor. - **/ -LinkManager::LinkManager(QObject* parent) - : QGCSingleton(parent) +LinkManager::LinkManager(QGCApplication* app) + : QGCTool(app) , _configUpdateSuspended(false) , _configurationsLoaded(false) , _connectionsSuspended(false) , _mavlinkChannelsUsedBitMask(0) , _nullSharedLink(NULL) + , _mavlinkProtocol(NULL) { -#ifndef __ios__ - connect(&_portListTimer, &QTimer::timeout, this, &LinkManager::_updateConfigurationList); - _portListTimer.start(1000); -#endif + } LinkManager::~LinkManager() @@ -80,6 +73,18 @@ LinkManager::~LinkManager() Q_ASSERT_X(_links.count() == 0, "LinkManager", "LinkManager::_shutdown should have been called previously"); } +void LinkManager::setToolbox(QGCToolbox *toolbox) +{ + QGCTool::setToolbox(toolbox); + + _mavlinkProtocol = _toolbox->mavlinkProtocol(); + +#ifndef __ios__ + connect(&_portListTimer, &QTimer::timeout, this, &LinkManager::_updateConfigurationList); + _portListTimer.start(1000); +#endif +} + LinkInterface* LinkManager::createConnectedLink(LinkConfiguration* config) { Q_ASSERT(config); @@ -149,16 +154,15 @@ void LinkManager::_addLink(LinkInterface* link) // MainWindow may be around when doing things like running unit tests if (MainWindow::instance()) { - connect(link, &LinkInterface::communicationError, qgcApp(), &QGCApplication::criticalMessageBoxOnMainThread); + connect(link, &LinkInterface::communicationError, _app, &QGCApplication::criticalMessageBoxOnMainThread); } - MAVLinkProtocol* mavlink = MAVLinkProtocol::instance(); - connect(link, &LinkInterface::bytesReceived, mavlink, &MAVLinkProtocol::receiveBytes); - connect(link, &LinkInterface::connected, mavlink, &MAVLinkProtocol::linkConnected); - connect(link, &LinkInterface::disconnected, mavlink, &MAVLinkProtocol::linkDisconnected); - mavlink->resetMetadataForLink(link); + connect(link, &LinkInterface::bytesReceived, _mavlinkProtocol, &MAVLinkProtocol::receiveBytes); + connect(link, &LinkInterface::connected, _mavlinkProtocol, &MAVLinkProtocol::linkConnected); + connect(link, &LinkInterface::disconnected, _mavlinkProtocol, &MAVLinkProtocol::linkDisconnected); + _mavlinkProtocol->resetMetadataForLink(link); - connect(link, &LinkInterface::connected, this, &LinkManager::_linkConnected); + connect(link, &LinkInterface::connected, this, &LinkManager::_linkConnected); connect(link, &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected); } diff --git a/src/comm/LinkManager.h b/src/comm/LinkManager.h index 24e3f8e85c251b0f27f99a5c2fc808c11c5fef2d..3063f50eb23ef7c86c458b6eca0444efd03bfb28 100644 --- a/src/comm/LinkManager.h +++ b/src/comm/LinkManager.h @@ -34,6 +34,7 @@ This file is part of the PIXHAWK project #include "LinkConfiguration.h" #include "LinkInterface.h" #include "QGCLoggingCategory.h" +#include "QGCToolbox.h" // Links #ifndef __ios__ @@ -48,12 +49,11 @@ This file is part of the PIXHAWK project #endif #include "ProtocolInterface.h" -#include "QGCSingleton.h" #include "MAVLinkProtocol.h" Q_DECLARE_LOGGING_CATEGORY(LinkManagerLog) -class LinkManagerTest; +class QGCApplication; /// Manage communication links /// @@ -61,16 +61,16 @@ class LinkManagerTest; /// links and takes care of connecting them as well assigning the correct /// protocol instance to transport the link data into the application. -class LinkManager : public QGCSingleton +class LinkManager : public QGCTool { Q_OBJECT - DECLARE_QGC_SINGLETON(LinkManager, LinkManager) /// Unit Test has access to private constructor/destructor friend class LinkManagerTest; public: - + LinkManager(QGCApplication* app); + ~LinkManager(); /*! Add a new link configuration setting to the list @@ -144,6 +144,9 @@ public: void _deleteLink(LinkInterface* link); void _addLink(LinkInterface* link); + // Override from QGCTool + virtual void setToolbox(QGCToolbox *toolbox); + signals: void newLink(LinkInterface* link); void linkDeleted(LinkInterface* link); @@ -156,10 +159,6 @@ private slots: void _linkDisconnected(void); private: - /// All access to LinkManager is through LinkManager::instance - LinkManager(QObject* parent = NULL); - ~LinkManager(); - virtual void _shutdown(void); bool _connectionsSuspendedMsg(void); @@ -186,6 +185,8 @@ private: uint32_t _mavlinkChannelsUsedBitMask; SharedLinkInterface _nullSharedLink; + + MAVLinkProtocol* _mavlinkProtocol; }; #endif diff --git a/src/comm/LogReplayLink.cc b/src/comm/LogReplayLink.cc index ca0d1fb3a11f3a289f30afc7e724e38d5d3f4ec2..d5ac20cebffc2e36a45e1a89c6543bade06128cc 100644 --- a/src/comm/LogReplayLink.cc +++ b/src/comm/LogReplayLink.cc @@ -23,6 +23,7 @@ #include "LogReplayLink.h" #include "LinkManager.h" +#include "QGCApplication.h" #include #include @@ -101,7 +102,7 @@ LogReplayLink::~LogReplayLink(void) bool LogReplayLink::_connect(void) { // Disallow replay when any links are connected - if (LinkManager::instance()->anyConnectedLinks()) { + if (qgcApp()->toolbox()->linkManager()->anyConnectedLinks()) { emit communicationError(_errorTitle, "You must close all connections prior to replaying a log."); return false; } @@ -366,9 +367,9 @@ void LogReplayLink::_readNextLogEntry(void) void LogReplayLink::_play(void) { // FIXME: With move to link I don't think this is needed any more? Except for the replay widget handling multi-uas? - LinkManager::instance()->setConnectionsSuspended(tr("Connect not allowed during Flight Data replay.")); + qgcApp()->toolbox()->linkManager()->setConnectionsSuspended(tr("Connect not allowed during Flight Data replay.")); #ifndef __mobile__ - MAVLinkProtocol::instance()->suspendLogForReplay(true); + qgcApp()->toolbox()->mavlinkProtocol()->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. @@ -398,9 +399,9 @@ void LogReplayLink::_play(void) void LogReplayLink::_pause(void) { - LinkManager::instance()->setConnectionsAllowed(); + qgcApp()->toolbox()->linkManager()->setConnectionsAllowed(); #ifndef __mobile__ - MAVLinkProtocol::instance()->suspendLogForReplay(false); + qgcApp()->toolbox()->mavlinkProtocol()->suspendLogForReplay(false); #endif _readTickTimer.stop(); diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index d221dc26e255633b0b062de16e496418b21b8415..a60d5538502cd82a399aadba095b7838a6b294b5 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -30,7 +30,7 @@ #include "MultiVehicleManager.h" Q_DECLARE_METATYPE(mavlink_message_t) -IMPLEMENT_QGC_SINGLETON(MAVLinkProtocol, MAVLinkProtocol) + QGC_LOGGING_CATEGORY(MAVLinkProtocolLog, "MAVLinkProtocolLog") #ifndef __mobile__ @@ -42,53 +42,30 @@ const char* MAVLinkProtocol::_logFileExtension = "mavlink"; ///< Ext * The default constructor will create a new MAVLink object sending heartbeats at * the MAVLINK_HEARTBEAT_DEFAULT_RATE to all connected links. */ -MAVLinkProtocol::MAVLinkProtocol(QObject* parent) : - QGCSingleton(parent), - m_multiplexingEnabled(false), - m_authEnabled(false), - m_enable_version_check(true), - m_paramRetransmissionTimeout(350), - m_paramRewriteTimeout(500), - m_paramGuardEnabled(true), - m_actionGuardEnabled(false), - m_actionRetransmissionTimeout(100), - versionMismatchIgnore(false), - systemId(QGC::defaultSystemId), +MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app) + : QGCTool(app) + , m_multiplexingEnabled(false) + , m_authEnabled(false) + , m_enable_version_check(true) + , m_paramRetransmissionTimeout(350) + , m_paramRewriteTimeout(500) + , m_paramGuardEnabled(true) + , m_actionGuardEnabled(false) + , m_actionRetransmissionTimeout(100) + , versionMismatchIgnore(false) + , systemId(QGC::defaultSystemId) #ifndef __mobile__ - _logSuspendError(false), - _logSuspendReplay(false), - _logWasArmed(false), - _tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension)), + , _logSuspendError(false) + , _logSuspendReplay(false) + , _logWasArmed(false) + , _tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension)) #endif - _linkMgr(LinkManager::instance()), - _heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE), - _heartbeatsEnabled(true) + , _heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE) + , _heartbeatsEnabled(true) + , _linkMgr(NULL) + , _multiVehicleManager(NULL) { - qRegisterMetaType("mavlink_message_t"); - - m_authKey = "xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx"; - 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(). - // Initialize the list for tracking dropped messages to invalid. - for (int i = 0; i < 256; i++) - { - for (int j = 0; j < 256; j++) - { - lastIndex[i][j] = -1; - } - } - - // Start heartbeat timer, emitting a heartbeat at the configured rate - connect(&_heartbeatTimer, &QTimer::timeout, this, &MAVLinkProtocol::sendHeartbeat); - _heartbeatTimer.start(1000/_heartbeatRate); - - connect(this, &MAVLinkProtocol::protocolStatusMessage, qgcApp(), &QGCApplication::criticalMessageBoxOnMainThread); - connect(this, &MAVLinkProtocol::saveTempFlightDataLog, qgcApp(), &QGCApplication::saveTempFlightDataLogOnMainThread); - - emit versionCheckChanged(m_enable_version_check); } MAVLinkProtocol::~MAVLinkProtocol() @@ -100,6 +77,40 @@ MAVLinkProtocol::~MAVLinkProtocol() #endif } +void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox) +{ + QGCTool::setToolbox(toolbox); + + _linkMgr = _toolbox->linkManager(); + _multiVehicleManager = _toolbox->multiVehicleManager(); + + qRegisterMetaType("mavlink_message_t"); + + m_authKey = "xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx"; + 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(). + + // Initialize the list for tracking dropped messages to invalid. + for (int i = 0; i < 256; i++) + { + for (int j = 0; j < 256; j++) + { + lastIndex[i][j] = -1; + } + } + + // Start heartbeat timer, emitting a heartbeat at the configured rate + connect(&_heartbeatTimer, &QTimer::timeout, this, &MAVLinkProtocol::sendHeartbeat); + _heartbeatTimer.start(1000/_heartbeatRate); + + connect(this, &MAVLinkProtocol::protocolStatusMessage, _app, &QGCApplication::criticalMessageBoxOnMainThread); + connect(this, &MAVLinkProtocol::saveTempFlightDataLog, _app, &QGCApplication::saveTempFlightDataLogOnMainThread); + + emit versionCheckChanged(m_enable_version_check); +} + void MAVLinkProtocol::loadSettings() { // Load defaults from settings @@ -185,7 +196,7 @@ void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected) } // Use the same shared pointer as LinkManager - _connectedLinks.append(LinkManager::instance()->sharedPointerForLink(link)); + _connectedLinks.append(_linkMgr->sharedPointerForLink(link)); #ifndef __mobile__ if (_connectedLinks.count() == 1) { @@ -235,7 +246,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) // 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. - if (!LinkManager::instance()->containsLink(link)) { + if (!_linkMgr->containsLink(link)) { return; } @@ -356,7 +367,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) // Notify the vehicle manager of the heartbeat. This will create/update vehicles as needed. mavlink_heartbeat_t heartbeat; mavlink_msg_heartbeat_decode(&message, &heartbeat); - if (!MultiVehicleManager::instance()->notifyHeartbeatInfo(link, message.sysid, heartbeat)) { + if (!_multiVehicleManager->notifyHeartbeatInfo(link, message.sysid, heartbeat)) { continue; } } @@ -667,7 +678,7 @@ void MAVLinkProtocol::_stopLogging(void) { if (_closeLogFile()) { // If the signals are not connected it means we are running a unit test. In that case just delete log files - if (_logWasArmed && qgcApp()->promptFlightDataSave()) { + if (_logWasArmed && _app->promptFlightDataSave()) { emit saveTempFlightDataLog(_tempLogFile.fileName()); } else { QFile::remove(_tempLogFile.fileName()); diff --git a/src/comm/MAVLinkProtocol.h b/src/comm/MAVLinkProtocol.h index 2549e0aa587d4ec716baa5390e6312b71c2ec96b..31b70b8d7cd64427d7b14967a4cfddabe0fc88c1 100644 --- a/src/comm/MAVLinkProtocol.h +++ b/src/comm/MAVLinkProtocol.h @@ -43,9 +43,11 @@ This file is part of the QGROUNDCONTROL project #include "QGCMAVLink.h" #include "QGC.h" #include "QGCTemporaryFile.h" -#include "QGCSingleton.h" +#include "QGCToolbox.h" class LinkManager; +class MultiVehicleManager; +class QGCApplication; Q_DECLARE_LOGGING_CATEGORY(MAVLinkProtocolLog) @@ -56,13 +58,14 @@ Q_DECLARE_LOGGING_CATEGORY(MAVLinkProtocolLog) * for more information, please see the official website. * @ref http://pixhawk.ethz.ch/software/mavlink/ **/ -class MAVLinkProtocol : public QGCSingleton +class MAVLinkProtocol : public QGCTool { Q_OBJECT - - DECLARE_QGC_SINGLETON(MAVLinkProtocol, MAVLinkProtocol) public: + MAVLinkProtocol(QGCApplication* app); + ~MAVLinkProtocol(); + /** @brief Get the human-friendly name of this protocol */ QString getName(); /** @brief Get the system id of this application */ @@ -145,6 +148,9 @@ public: /// Suspend/Restart logging during replay. void suspendLogForReplay(bool suspend); + // Override from QGCTool + virtual void setToolbox(QGCToolbox *toolbox); + public slots: /** @brief Receive bytes from a communication interface */ void receiveBytes(LinkInterface* link, QByteArray b); @@ -279,9 +285,6 @@ signals: void saveTempFlightDataLog(QString tempLogfile); private: - MAVLinkProtocol(QObject* parent = NULL); - ~MAVLinkProtocol(); - void _linkStatusChanged(LinkInterface* link, bool connected); #ifndef __mobile__ @@ -303,11 +306,12 @@ private: /// This way Link deletion works correctly. QList _connectedLinks; - LinkManager* _linkMgr; - QTimer _heartbeatTimer; ///< Timer to emit heartbeats int _heartbeatRate; ///< Heartbeat rate, controls the timer interval bool _heartbeatsEnabled; ///< Enabled/disable heartbeat emission + + LinkManager* _linkMgr; + MultiVehicleManager* _multiVehicleManager; }; #endif // MAVLINKPROTOCOL_H_ diff --git a/src/comm/MockLink.cc b/src/comm/MockLink.cc index b704198fa6b561bb7b7666e53125d9ae937d03ae..1c0a8965928c3f93ee9df07e82341f6058efaae2 100644 --- a/src/comm/MockLink.cc +++ b/src/comm/MockLink.cc @@ -23,6 +23,7 @@ #include "MockLink.h" #include "QGCLoggingCategory.h" +#include "QGCApplication.h" #include #include @@ -76,7 +77,7 @@ const char* MockConfiguration::_vehicleTypeKey = "VehicleType"; const char* MockConfiguration::_sendStatusTextKey = "SendStatusText"; MockLink::MockLink(MockConfiguration* config) - : _missionItemHandler(this) + : _missionItemHandler(this, qgcApp()->toolbox()->mavlinkProtocol()) , _name("MockLink") , _connected(false) , _vehicleSystemId(128) // FIXME: Pull from eventual parameter manager diff --git a/src/comm/MockLinkMissionItemHandler.cc b/src/comm/MockLinkMissionItemHandler.cc index 13d5ca0fd5dc32132ff097e4cbc55ce35130d1f0..42527cce377e8b770694cf4590a61d2965cb7046 100644 --- a/src/comm/MockLinkMissionItemHandler.cc +++ b/src/comm/MockLinkMissionItemHandler.cc @@ -28,11 +28,12 @@ QGC_LOGGING_CATEGORY(MockLinkMissionItemHandlerLog, "MockLinkMissionItemHandlerLog") -MockLinkMissionItemHandler::MockLinkMissionItemHandler(MockLink* mockLink) +MockLinkMissionItemHandler::MockLinkMissionItemHandler(MockLink* mockLink, MAVLinkProtocol* mavlinkProtocol) : _mockLink(mockLink) , _missionItemResponseTimer(NULL) , _failureMode(FailNone) , _sendHomePositionOnEmptyList(false) + , _mavlinkProtocol(mavlinkProtocol) { Q_ASSERT(mockLink); } @@ -234,8 +235,8 @@ void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber) mavlink_message_t message; mavlink_mission_request_t missionRequest; - missionRequest.target_system = MAVLinkProtocol::instance()->getSystemId(); - missionRequest.target_component = MAVLinkProtocol::instance()->getComponentId(); + missionRequest.target_system = _mavlinkProtocol->getSystemId(); + missionRequest.target_component = _mavlinkProtocol->getComponentId(); missionRequest.seq = sequenceNumber; mavlink_msg_mission_request_encode(_mockLink->vehicleId(), MAV_COMP_ID_MISSIONPLANNER, &message, &missionRequest); @@ -258,8 +259,8 @@ void MockLinkMissionItemHandler::_sendAck(MAV_MISSION_RESULT ackType) mavlink_message_t message; mavlink_mission_ack_t missionAck; - missionAck.target_system = MAVLinkProtocol::instance()->getSystemId(); - missionAck.target_component = MAVLinkProtocol::instance()->getComponentId(); + missionAck.target_system = _mavlinkProtocol->getSystemId(); + missionAck.target_component = _mavlinkProtocol->getComponentId(); missionAck.type = ackType; mavlink_msg_mission_ack_encode(_mockLink->vehicleId(), MAV_COMP_ID_MISSIONPLANNER, &message, &missionAck); diff --git a/src/comm/MockLinkMissionItemHandler.h b/src/comm/MockLinkMissionItemHandler.h index 1405e503776e4a032c752bd6a0e1a82529ef5846..4f7e7da44e1dcd4074470956727cd3581affff54 100644 --- a/src/comm/MockLinkMissionItemHandler.h +++ b/src/comm/MockLinkMissionItemHandler.h @@ -30,6 +30,7 @@ #include "QGCMAVLink.h" #include "QGCLoggingCategory.h" +#include "MAVLinkProtocol.h" class MockLink; @@ -40,7 +41,7 @@ class MockLinkMissionItemHandler : public QObject Q_OBJECT public: - MockLinkMissionItemHandler(MockLink* mockLink); + MockLinkMissionItemHandler(MockLink* mockLink, MAVLinkProtocol* mavlinkProtocol); ~MockLinkMissionItemHandler(); // Prepares for destruction on correct thread @@ -111,10 +112,11 @@ private: typedef QMap MissionList_t; MissionList_t _missionItems; - QTimer* _missionItemResponseTimer; - FailureMode_t _failureMode; - bool _failureFirstTimeOnly; - bool _sendHomePositionOnEmptyList; + QTimer* _missionItemResponseTimer; + FailureMode_t _failureMode; + bool _failureFirstTimeOnly; + bool _sendHomePositionOnEmptyList; + MAVLinkProtocol* _mavlinkProtocol; }; #endif diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index 112ef3985d51761b9598893a799798258fcc0890..cf70786c3094fe5d79e0824c6b07d25a3d5cb51f 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -46,6 +46,7 @@ This file is part of the QGROUNDCONTROL project #include "QGCFileDialog.h" #include "QGCMessageBox.h" #include "HomePositionManager.h" +#include "QGCApplication.h" // FlightGear _fgProcess start and connection is quite fragile. Uncomment the define below to get higher level of debug output // for tracking down problems. @@ -957,11 +958,11 @@ bool QGCFlightGearLink::connectSimulation() } // We start out at our home position - _fgArgList << QString("--lat=%1").arg(HomePositionManager::instance()->getHomeLatitude()); - _fgArgList << QString("--lon=%1").arg(HomePositionManager::instance()->getHomeLongitude()); + _fgArgList << QString("--lat=%1").arg(qgcApp()->toolbox()->homePositionManager()->getHomeLatitude()); + _fgArgList << QString("--lon=%1").arg(qgcApp()->toolbox()->homePositionManager()->getHomeLongitude()); // The altitude is not set because an altitude not equal to the ground altitude leads to a non-zero default throttle in flightgear // Without the altitude-setting the aircraft is positioned on the ground - //_fgArgList << QString("--altitude=%1").arg(HomePositionManager::instance()->getHomeAltitude()); + //_fgArgList << QString("--altitude=%1").arg(qgcApp()->toolbox()->homePositionManager()->getHomeAltitude()); #ifdef DEBUG_FLIGHTGEAR_CONNECT // This tell FlightGear to output highest debug level of log output. Handy for debuggin failures by looking at the FG diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index 68c0f9700dbf352a020ec0e1e2d6227758aeb324..73e0755e73d17e021ceeca794e65e1f7b1fa6892 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -133,7 +133,7 @@ bool SerialLink::_disconnect(void) } #ifdef __android__ - LinkManager::instance()->suspendConfigurationUpdates(false); + qgcApp()->toolbox()->linkManager()->suspendConfigurationUpdates(false); #endif return true; } @@ -150,7 +150,7 @@ bool SerialLink::_connect(void) _disconnect(); #ifdef __android__ - LinkManager::instance()->suspendConfigurationUpdates(true); + qgcApp()->toolbox()->linkManager()->suspendConfigurationUpdates(true); #endif // Initialize the connection diff --git a/src/input/Mouse6dofInput.cpp b/src/input/Mouse6dofInput.cpp index f092616c2995d845906dc4298127d0329873eeeb..d1c5956ea0daf0874df79edeb3ba7214ae32ea9e 100644 --- a/src/input/Mouse6dofInput.cpp +++ b/src/input/Mouse6dofInput.cpp @@ -38,7 +38,7 @@ Mouse6dofInput::Mouse6dofInput(Mouse3DInput* mouseInput) : bValue(0.0), cValue(0.0) { - connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &Mouse6dofInput::_activeVehicleChanged); + connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &Mouse6dofInput::_activeVehicleChanged); // Connect 3DxWare SDK MotionEvent connect(mouseInput, SIGNAL(Move3d(std::vector&)), this, SLOT(motion3DMouse(std::vector&))); @@ -63,7 +63,7 @@ Mouse6dofInput::Mouse6dofInput(QWidget* parent) : bValue(0.0), cValue(0.0) { - connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &Mouse6dofInput::_activeVehicleChanged); + connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &Mouse6dofInput::_activeVehicleChanged); if (!mouseActive) { @@ -137,7 +137,7 @@ void Mouse6dofInput::_activeVehicleChanged(Vehicle* vehicle) void Mouse6dofInput::init() { // Make sure active UAS is set - _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle()); + _activeVehicleChanged(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()); } void Mouse6dofInput::run() diff --git a/src/qgcunittest/FileManagerTest.cc b/src/qgcunittest/FileManagerTest.cc index 1ea71193b897d672bcde455fc80114932bac4eed..54eae9353cf674908453d3ec567b5096a0160ad2 100644 --- a/src/qgcunittest/FileManagerTest.cc +++ b/src/qgcunittest/FileManagerTest.cc @@ -27,14 +27,14 @@ #include "FileManagerTest.h" #include "MultiVehicleManager.h" #include "UAS.h" +#include "QGCApplication.h" //UT_REGISTER_TEST(FileManagerTest) -FileManagerTest::FileManagerTest(void) : - _mockLink(NULL), - _fileServer(NULL), - _fileManager(NULL), - _multiSpy(NULL) +FileManagerTest::FileManagerTest(void) + : _fileServer(NULL) + , _fileManager(NULL) + , _multiSpy(NULL) { } @@ -44,24 +44,12 @@ void FileManagerTest::init(void) { UnitTest::init(); - _mockLink = new MockLink(); - Q_CHECK_PTR(_mockLink); - LinkManager::instance()->_addLink(_mockLink); - LinkManager::instance()->connectLink(_mockLink); + _connectMockLink(); _fileServer = _mockLink->getFileServer(); QVERIFY(_fileServer != NULL); - // Wait or the Vehicle to show up - MultiVehicleManager* vehicleManager = MultiVehicleManager::instance(); - QSignalSpy spyVehicleCreate(vehicleManager, SIGNAL(activeVehicleChanged(Vehicle*))); - if (!vehicleManager->activeVehicle()) { - QCOMPARE(spyVehicleCreate.wait(10000), true); - } - UASInterface* uas = vehicleManager->activeVehicle()->uas(); - QVERIFY(uas != NULL); - - _fileManager = uas->getFileManager(); + _fileManager = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->uas()->getFileManager(); QVERIFY(_fileManager != NULL); Q_ASSERT(_multiSpy == NULL); @@ -89,9 +77,9 @@ void FileManagerTest::cleanup(void) // Disconnecting the link will prompt for log file save setExpectedFileDialog(getSaveFileName, QStringList()); - LinkManager::instance()->disconnectLink(_mockLink); + _disconnectMockLink(); + _fileServer = NULL; - _mockLink = NULL; _fileManager = NULL; delete _multiSpy; diff --git a/src/qgcunittest/FileManagerTest.h b/src/qgcunittest/FileManagerTest.h index 04520311a0281f7e572b8c1e53fe86ddceab048a..280f3352509d6732c8b78594084665863da2409b 100644 --- a/src/qgcunittest/FileManagerTest.h +++ b/src/qgcunittest/FileManagerTest.h @@ -76,7 +76,6 @@ private: static const uint8_t _systemIdQGC = 255; static const uint8_t _systemIdServer = 128; - MockLink* _mockLink; MockLinkFileServer* _fileServer; FileManager* _fileManager; diff --git a/src/qgcunittest/LinkManagerTest.cc b/src/qgcunittest/LinkManagerTest.cc index 67d143b582271a61c43f3b2da5833a9841f91223..3c522c35a0c7e8b9b0c67324fe2b3163f17e320e 100644 --- a/src/qgcunittest/LinkManagerTest.cc +++ b/src/qgcunittest/LinkManagerTest.cc @@ -28,6 +28,7 @@ #include "LinkManagerTest.h" #include "MockLink.h" +#include "QGCApplication.h" UT_REGISTER_TEST(LinkManagerTest) @@ -45,7 +46,7 @@ void LinkManagerTest::init(void) Q_ASSERT(_linkMgr == NULL); Q_ASSERT(_multiSpy == NULL); - _linkMgr = new LinkManager(NULL /* no parent */); + _linkMgr = qgcApp()->toolbox()->linkManager(); Q_CHECK_PTR(_linkMgr); _rgSignals[newLinkSignalIndex] = SIGNAL(newLink(LinkInterface*)); @@ -60,9 +61,6 @@ void LinkManagerTest::cleanup(void) Q_ASSERT(_linkMgr); Q_ASSERT(_multiSpy); - _linkMgr->_shutdown(); - - delete _linkMgr; delete _multiSpy; _linkMgr = NULL; @@ -77,12 +75,11 @@ void LinkManagerTest::_add_test(void) Q_ASSERT(_linkMgr); Q_ASSERT(_linkMgr->getLinks().count() == 0); - MockLink* link = new MockLink(); - _linkMgr->_addLink(link); + _connectMockLink(); QList links = _linkMgr->getLinks(); QCOMPARE(links.count(), 1); - QCOMPARE(dynamic_cast(links[0]), link); + QCOMPARE(dynamic_cast(links[0]), _mockLink); } void LinkManagerTest::_delete_test(void) @@ -90,9 +87,8 @@ void LinkManagerTest::_delete_test(void) Q_ASSERT(_linkMgr); Q_ASSERT(_linkMgr->getLinks().count() == 0); - MockLink* link = new MockLink(); - _linkMgr->_addLink(link); - _linkMgr->_deleteLink(link); + _connectMockLink(); + _disconnectMockLink(); QCOMPARE(_linkMgr->getLinks().count(), 0); } @@ -103,9 +99,8 @@ void LinkManagerTest::_addSignals_test(void) Q_ASSERT(_linkMgr->getLinks().count() == 0); Q_ASSERT(_multiSpy->checkNoSignals() == true); - MockLink* link = new MockLink(); - _linkMgr->_addLink(link); - + _connectMockLink(); + QCOMPARE(_multiSpy->checkOnlySignalByMask(newLinkSignalMask), true); QSignalSpy* spy = _multiSpy->getSpyByIndex(newLinkSignalIndex); @@ -115,7 +110,7 @@ void LinkManagerTest::_addSignals_test(void) QObject* object = qvariant_cast(signalArgs[0]); QVERIFY(object != NULL); MockLink* signalLink = qobject_cast(object); - QCOMPARE(signalLink, link); + QCOMPARE(signalLink, _mockLink); } void LinkManagerTest::_deleteSignals_test(void) @@ -124,11 +119,9 @@ void LinkManagerTest::_deleteSignals_test(void) Q_ASSERT(_linkMgr->getLinks().count() == 0); Q_ASSERT(_multiSpy->checkNoSignals() == true); - MockLink* link = new MockLink(); - _linkMgr->_addLink(link); + _connectMockLink(); _multiSpy->clearAllSignals(); - - _linkMgr->_deleteLink(link); + _disconnectMockLink(); QCOMPARE(_multiSpy->checkOnlySignalByMask(linkDeletedSignalMask), true); QSignalSpy* spy = _multiSpy->getSpyByIndex(linkDeletedSignalIndex); diff --git a/src/qgcunittest/MainWindowTest.cc b/src/qgcunittest/MainWindowTest.cc index 95d0b0da34329be31350f7230d9f5a7860b45f1a..c360c84da8edf560cb5295f77414403f2a992c17 100644 --- a/src/qgcunittest/MainWindowTest.cc +++ b/src/qgcunittest/MainWindowTest.cc @@ -31,56 +31,18 @@ #include "QGCMessageBox.h" #include "MultiVehicleManager.h" -UT_REGISTER_TEST(MainWindowTest) - -MainWindowTest::MainWindowTest(void) : - _mainWindow() -{ - -} - -void MainWindowTest::init(void) -{ - UnitTest::init(); - - _mainWindow = MainWindow::_create(); - Q_CHECK_PTR(_mainWindow); -} - -void MainWindowTest::cleanup(void) -{ - _mainWindow->close(); - QTest::qWait(200); - delete _mainWindow; - - UnitTest::cleanup(); -} +// FIXME: Temporarily turned off +//UT_REGISTER_TEST(MainWindowTest) void MainWindowTest::_connectWindowClose_test(MAV_AUTOPILOT autopilot) { - LinkManager* linkMgr = LinkManager::instance(); - Q_CHECK_PTR(linkMgr); - - MockLink* link = new MockLink(); - Q_CHECK_PTR(link); - link->setFirmwareType(autopilot); - LinkManager::instance()->_addLink(link); - - linkMgr->connectLink(link); - - // Wait for the Vehicle to work it's way through the various threads - - QSignalSpy spyVehicle(MultiVehicleManager::instance(), SIGNAL(activeVehicleChanged(Vehicle*))); - QCOMPARE(spyVehicle.wait(5000), true); + _createMainWindow(); + _connectMockLink(autopilot); // On MainWindow close we should get a message box telling the user to disconnect first. Cancel should do nothing. setExpectedMessageBox(QGCMessageBox::Cancel); - _mainWindow->close(); - QTest::qWait(1000); // Need to allow signals to move between threads + _closeMainWindow(true /* cancelExpected */); checkExpectedMessageBox(); - - linkMgr->disconnectLink(link); - QTest::qWait(1000); // Need to allow signals to move between threads } void MainWindowTest::_connectWindowClosePX4_test(void) { diff --git a/src/qgcunittest/MainWindowTest.h b/src/qgcunittest/MainWindowTest.h index 8c9d3fafd622107dad0a2952e58b7a717c419418..3b9ddc5fa76bc10311803ff8d8185f39370c888f 100644 --- a/src/qgcunittest/MainWindowTest.h +++ b/src/qgcunittest/MainWindowTest.h @@ -36,20 +36,12 @@ class MainWindowTest : public UnitTest { Q_OBJECT -public: - MainWindowTest(void); - private slots: - void init(void); - void cleanup(void); - void _connectWindowClosePX4_test(void); void _connectWindowCloseGeneric_test(void); private: void _connectWindowClose_test(MAV_AUTOPILOT autopilot); - - MainWindow* _mainWindow; }; #endif diff --git a/src/qgcunittest/MavlinkLogTest.cc b/src/qgcunittest/MavlinkLogTest.cc index 3c30610b76ba9f48522c12a6689a97fe3bc8663b..766cb9e1e852e9b8d7174e3544b255e9db257d6b 100644 --- a/src/qgcunittest/MavlinkLogTest.cc +++ b/src/qgcunittest/MavlinkLogTest.cc @@ -92,7 +92,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, MAVLinkProtocol::instance(), &MAVLinkProtocol::checkForLostLogFiles); + connect(this, &MavlinkLogTest::checkForLostLogFiles, qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::checkForLostLogFiles); emit checkForLostLogFiles(); QTest::qWait(1000); @@ -112,7 +112,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, MAVLinkProtocol::instance(), &MAVLinkProtocol::checkForLostLogFiles); + connect(this, &MavlinkLogTest::checkForLostLogFiles, qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::checkForLostLogFiles); emit checkForLostLogFiles(); QTest::qWait(1000); @@ -129,7 +129,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, MAVLinkProtocol::instance(), &MAVLinkProtocol::checkForLostLogFiles); + connect(this, &MavlinkLogTest::checkForLostLogFiles, qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::checkForLostLogFiles); emit checkForLostLogFiles(); QTest::qWait(1000); @@ -138,23 +138,12 @@ void MavlinkLogTest::_bootLogDetectionZeroLength_test(void) void MavlinkLogTest::_connectLogWorker(bool arm) { - LinkManager* linkMgr = LinkManager::instance(); - Q_CHECK_PTR(linkMgr); - - MockLink* link = new MockLink(); - Q_CHECK_PTR(link); - LinkManager::instance()->_addLink(link); - linkMgr->connectLink(link); - - // Wait for the uas to work it's way through the various threads - - QSignalSpy spyVehicle(MultiVehicleManager::instance(), SIGNAL(activeVehicleChanged(Vehicle*))); - QCOMPARE(spyVehicle.wait(5000), true); + _connectMockLink(); QDir logSaveDir; if (arm) { - MultiVehicleManager::instance()->activeVehicle()->setArmed(true); + qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->setArmed(true); QTest::qWait(1500); // Wait long enough for heartbeat to come through // On Disconnect: We should get a getSaveFileName dialog. @@ -163,8 +152,7 @@ void MavlinkLogTest::_connectLogWorker(bool arm) setExpectedFileDialog(getSaveFileName, QStringList(logSaveFile)); } - linkMgr->disconnectLink(link); - QTest::qWait(1000); // Need to allow signals to move between threads + _disconnectMockLink(); if (arm) { checkExpectedFileDialog(); diff --git a/src/qgcunittest/PX4RCCalibrationTest.cc b/src/qgcunittest/PX4RCCalibrationTest.cc index d6c13a2555a7ed508f5073954035bcb82807e159..3aec7f6227e4b70abbfdcf68d92be8780d93227f 100644 --- a/src/qgcunittest/PX4RCCalibrationTest.cc +++ b/src/qgcunittest/PX4RCCalibrationTest.cc @@ -24,6 +24,7 @@ #include "PX4RCCalibrationTest.h" #include "RadioComponentController.h" #include "MultiVehicleManager.h" +#include "QGCApplication.h" /// @file /// @brief QRadioComponentController Widget unit test @@ -149,18 +150,9 @@ void RadioConfigTest::init(void) { UnitTest::init(); - _mockLink = new MockLink(); - Q_CHECK_PTR(_mockLink); - LinkManager::instance()->_addLink(_mockLink); - LinkManager::instance()->connectLink(_mockLink); + _connectMockLink(); - // Wait for the Vehicle to get created - QSignalSpy spyVehicle(MultiVehicleManager::instance(), SIGNAL(parameterReadyVehicleAvailableChanged(bool))); - QCOMPARE(spyVehicle.wait(5000), true); - QVERIFY(MultiVehicleManager::instance()->parameterReadyVehicleAvailable()); - QVERIFY(MultiVehicleManager::instance()->activeVehicle()); - - _autopilot = MultiVehicleManager::instance()->activeVehicle()->autopilotPlugin(); + _autopilot = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->autopilotPlugin(); Q_ASSERT(_autopilot); // This will instatiate the widget with an active uas with ready parameters @@ -192,8 +184,6 @@ void RadioConfigTest::cleanup(void) // Disconnecting the link will prompt for log file save setExpectedFileDialog(getSaveFileName, QStringList()); - LinkManager::instance()->disconnectLink(_mockLink); - UnitTest::cleanup(); } diff --git a/src/qgcunittest/PX4RCCalibrationTest.h b/src/qgcunittest/PX4RCCalibrationTest.h index 585c66ae48430bf6cab90cd3afbd8384a888a11c..86517bbe1d32b5c641251016875d69b45dc961f2 100644 --- a/src/qgcunittest/PX4RCCalibrationTest.h +++ b/src/qgcunittest/PX4RCCalibrationTest.h @@ -94,7 +94,6 @@ private: void _validateParameters(void); - MockLink* _mockLink; AutoPilotPlugin* _autopilot; QGCQmlWidgetHolder* _calWidget; diff --git a/src/qgcunittest/UnitTest.cc b/src/qgcunittest/UnitTest.cc index bf901de7a4059094cd451254e06c16f82d479424..8d749c5ca84697d0dedd11cd62b43121e503eac2 100644 --- a/src/qgcunittest/UnitTest.cc +++ b/src/qgcunittest/UnitTest.cc @@ -29,6 +29,7 @@ #include "UnitTest.h" #include "QGCApplication.h" #include "MAVLinkProtocol.h" +#include "MainWindow.h" bool UnitTest::_messageBoxRespondedTo = false; bool UnitTest::_badResponseButton = false; @@ -41,14 +42,17 @@ QStringList UnitTest::_fileDialogResponse; enum UnitTest::FileDialogType UnitTest::_fileDialogExpectedType = getOpenFileName; int UnitTest::_missedFileDialogCount = 0; -UnitTest::UnitTest(void) : - _expectMissedFileDialog(false), - _expectMissedMessageBox(false), - _unitTestRun(false), - _initCalled(false), - _cleanupCalled(false) -{ - +UnitTest::UnitTest(void) + : _linkManager(NULL) + , _mockLink(NULL) + , _mainWindow(NULL) + , _expectMissedFileDialog(false) + , _expectMissedMessageBox(false) + , _unitTestRun(false) + , _initCalled(false) + , _cleanupCalled(false) +{ + } UnitTest::~UnitTest() @@ -101,6 +105,11 @@ int UnitTest::run(QString& singleTest) void UnitTest::init(void) { _initCalled = true; + + if (!_linkManager) { + _linkManager = qgcApp()->toolbox()->linkManager(); + connect(_linkManager, &LinkManager::linkDeleted, this, &UnitTest::_linkDeleted); + } _messageBoxRespondedTo = false; _missedMessageBoxCount = 0; @@ -128,6 +137,9 @@ void UnitTest::cleanup(void) { _cleanupCalled = true; + _disconnectMockLink(); + _closeMainWindow(); + // We add a slight delay here to allow for deleteLater and Qml cleanup QTest::qWait(200); @@ -358,3 +370,58 @@ QString UnitTest::_getSaveFileName( return _fileDialogResponseSingle(getSaveFileName); } + +void UnitTest::_connectMockLink(MAV_AUTOPILOT autopilot) +{ + Q_ASSERT(!_mockLink); + + _mockLink = new MockLink(); + _mockLink->setFirmwareType(autopilot); + + _linkManager->_addLink(_mockLink); + _linkManager->connectLink(_mockLink); + + // Wait for the Vehicle to get created + QSignalSpy spyVehicle(qgcApp()->toolbox()->multiVehicleManager(), SIGNAL(parameterReadyVehicleAvailableChanged(bool))); + QCOMPARE(spyVehicle.wait(5000), true); + QVERIFY(qgcApp()->toolbox()->multiVehicleManager()->parameterReadyVehicleAvailable()); + QVERIFY(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()); +} + +void UnitTest::_disconnectMockLink(void) +{ + if (_mockLink) { + QSignalSpy linkSpy(_linkManager, SIGNAL(linkDeleted(LinkInterface*))); + + _linkManager->disconnectLink(_mockLink); + + // Wait for link to go away + linkSpy.wait(1000); + QCOMPARE(linkSpy.count(), 1); + } +} + +void UnitTest::_linkDeleted(LinkInterface* link) +{ + if (link == _mockLink) { + _mockLink = NULL; + } +} + +void UnitTest::_createMainWindow(void) +{ + _mainWindow = MainWindow::_create(); + Q_CHECK_PTR(_mainWindow); +} + +void UnitTest::_closeMainWindow(bool cancelExpected) +{ + if (_mainWindow) { + QSignalSpy mainWindowSpy(_mainWindow, SIGNAL(mainWindowClosed())); + + _mainWindow->close(); + + mainWindowSpy.wait(2000); + QCOMPARE(mainWindowSpy.count(), cancelExpected ? 0 : 1); + } +} diff --git a/src/qgcunittest/UnitTest.h b/src/qgcunittest/UnitTest.h index 1046d603477bcb7e0e1e83f22b39140c076c10bf..a05855b179fb4bc168d0492cdccaf87938d3845e 100644 --- a/src/qgcunittest/UnitTest.h +++ b/src/qgcunittest/UnitTest.h @@ -35,11 +35,16 @@ #include #include +#include "QGCMAVLink.h" +#include "LinkInterface.h" + #define UT_REGISTER_TEST(className) static UnitTestWrapper t(#className); class QGCMessageBox; class QGCFileDialog; -class UnitTest; +class LinkManager; +class MockLink; +class MainWindow; class UnitTest : public QObject { @@ -102,9 +107,21 @@ protected slots: virtual void cleanup(void); protected: + void _connectMockLink(MAV_AUTOPILOT autopilot = MAV_AUTOPILOT_PX4); + void _disconnectMockLink(void); + void _createMainWindow(void); + void _closeMainWindow(bool cancelExpected = false); + + LinkManager* _linkManager; + MockLink* _mockLink; + MainWindow* _mainWindow; + bool _expectMissedFileDialog; // true: expect a missed file dialog, used for internal testing bool _expectMissedMessageBox; // true: expect a missed message box, used for internal testing - + +private slots: + void _linkDeleted(LinkInterface* link); + private: // When the app is running in unit test mode the QGCMessageBox methods are re-routed here. diff --git a/src/uas/FileManager.cc b/src/uas/FileManager.cc index dc3fe1a56eae4beb2dd4baa71044267f7efe8555..4c34284ed3ccaedd75e8252a33b11f4a56f3fbb9 100644 --- a/src/uas/FileManager.cc +++ b/src/uas/FileManager.cc @@ -26,6 +26,7 @@ #include "MAVLinkProtocol.h" #include "MainWindow.h" #include "Vehicle.h" +#include "QGCApplication.h" #include #include @@ -718,7 +719,7 @@ void FileManager::_sendRequest(Request* request) qCDebug(FileManagerLog) << "_sendRequest opcode:" << request->hdr.opcode << "seqNumber:" << request->hdr.seqNumber; if (_systemIdQGC == 0) { - _systemIdQGC = MAVLinkProtocol::instance()->getSystemId(); + _systemIdQGC = qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(); } Q_ASSERT(_vehicle); diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 230667be69af8bf40b46df1b476e143d010f9f90..a2b560333c2fdec9850919bc22e282ae26eacb25 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -50,7 +50,7 @@ QGC_LOGGING_CATEGORY(UASLog, "UASLog") * creating the UAS. */ -UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle) : UASInterface(), +UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * firmwarePluginManager) : UASInterface(), lipoFull(4.2f), lipoEmpty(3.5f), uasId(vehicle->id()), @@ -177,7 +177,8 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle) : UASInterface(), lastSendTimeGPS(0), lastSendTimeSensors(0), lastSendTimeOpticalFlow(0), - _vehicle(vehicle) + _vehicle(vehicle), + _firmwarePluginManager(firmwarePluginManager) { for (unsigned int i = 0; i<255;++i) @@ -398,7 +399,7 @@ void UAS::receiveMessage(mavlink_message_t message) bool statechanged = false; bool modechanged = false; - QString audiomodeText = FirmwarePluginManager::instance()->firmwarePluginForAutopilot((MAV_AUTOPILOT)state.autopilot, (MAV_TYPE)state.type)->flightMode(state.base_mode, state.custom_mode); + QString audiomodeText = _firmwarePluginManager->firmwarePluginForAutopilot((MAV_AUTOPILOT)state.autopilot, (MAV_TYPE)state.type)->flightMode(state.base_mode, state.custom_mode); if ((state.system_status != this->status) && state.system_status != MAV_STATE_UNINIT) { @@ -443,7 +444,7 @@ void UAS::receiveMessage(mavlink_message_t message) if (statechanged && ((int)state.system_status == (int)MAV_STATE_CRITICAL || state.system_status == (int)MAV_STATE_EMERGENCY)) { _say(QString("Emergency for system %1").arg(this->getUASID()), GAudioOutput::AUDIO_SEVERITY_EMERGENCY); - QTimer::singleShot(3000, GAudioOutput::instance(), SLOT(startEmergency())); + QTimer::singleShot(3000, qgcApp()->toolbox()->audioOutput(), SLOT(startEmergency())); } else if (modechanged || statechanged) { @@ -1058,28 +1059,7 @@ void UAS::receiveMessage(mavlink_message_t message) emit NavigationControllerDataChanged(this, p.nav_roll, p.nav_pitch, p.nav_bearing, p.target_bearing, p.wp_dist); } break; - // Messages to ignore - case MAVLINK_MSG_ID_RAW_IMU: - case MAVLINK_MSG_ID_SCALED_IMU: - case MAVLINK_MSG_ID_RAW_PRESSURE: - case MAVLINK_MSG_ID_SCALED_PRESSURE: - case MAVLINK_MSG_ID_OPTICAL_FLOW: - case MAVLINK_MSG_ID_DEBUG_VECT: - case MAVLINK_MSG_ID_DEBUG: - case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT: - case MAVLINK_MSG_ID_NAMED_VALUE_INT: - case MAVLINK_MSG_ID_MANUAL_CONTROL: - case MAVLINK_MSG_ID_HIGHRES_IMU: - case MAVLINK_MSG_ID_DISTANCE_SENSOR: - break; default: - { - if (!unknownPackets.contains(message.msgid)) - { - unknownPackets.append(message.msgid); - qDebug() << "Unknown message from system:" << uasId << "message:" << message.msgid; - } - } break; } } @@ -2474,5 +2454,5 @@ void UAS::unsetRCToParameterMap() void UAS::_say(const QString& text, int severity) { if (!qgcApp()->runningUnitTests()) - GAudioOutput::instance()->say(text, severity); + qgcApp()->toolbox()->audioOutput()->say(text, severity); } diff --git a/src/uas/UAS.h b/src/uas/UAS.h index ff03ce4f04881cef075dfb05770187e14373bdb0..cd52382c475d4ecdc89c794c27ba3ac7a8c0f946 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -38,6 +38,7 @@ This file is part of the QGROUNDCONTROL project #include "QGCMAVLink.h" #include "FileManager.h" #include "Vehicle.h" +#include "FirmwarePluginManager.h" #ifndef __mobile__ #include "QGCHilLink.h" @@ -62,7 +63,7 @@ class UAS : public UASInterface { Q_OBJECT public: - UAS(MAVLinkProtocol* protocol, Vehicle* vehicle); + UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * firmwarePluginManager); ~UAS(); float lipoFull; ///< 100% charged voltage @@ -695,7 +696,8 @@ private: void _say(const QString& text, int severity = 6); private: - Vehicle* _vehicle; + Vehicle* _vehicle; + FirmwarePluginManager* _firmwarePluginManager; }; diff --git a/src/uas/UASMessageHandler.cc b/src/uas/UASMessageHandler.cc index d95b770215523fb00e88ac99aaa6318969a0b77d..7582bd2e2749e944abe918cb0768683328988c74 100644 --- a/src/uas/UASMessageHandler.cc +++ b/src/uas/UASMessageHandler.cc @@ -52,20 +52,17 @@ bool UASMessage::severityIsError() } } -IMPLEMENT_QGC_SINGLETON(UASMessageHandler, UASMessageHandler) - -UASMessageHandler::UASMessageHandler(QObject *parent) - : QGCSingleton(parent) +UASMessageHandler::UASMessageHandler(QGCApplication* app) + : QGCTool(app) , _activeUAS(NULL) , _errorCount(0) , _errorCountTotal(0) , _warningCount(0) , _normalCount(0) , _showErrorsInToolbar(false) + , _multiVehicleManager(NULL) { - connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &UASMessageHandler::_activeVehicleChanged); - emit textMessageReceived(NULL); - emit textMessageCountChanged(0); + } UASMessageHandler::~UASMessageHandler() @@ -73,6 +70,17 @@ UASMessageHandler::~UASMessageHandler() clearMessages(); } +void UASMessageHandler::setToolbox(QGCToolbox *toolbox) +{ + QGCTool::setToolbox(toolbox); + + _multiVehicleManager = _toolbox->multiVehicleManager(); + + connect(_multiVehicleManager, &MultiVehicleManager::activeVehicleChanged, this, &UASMessageHandler::_activeVehicleChanged); + emit textMessageReceived(NULL); + emit textMessageCountChanged(0); +} + void UASMessageHandler::clearMessages() { _mutex.lock(); @@ -190,7 +198,7 @@ void UASMessageHandler::handleTextMessage(int, int compId, int severity, QString emit textMessageCountChanged(count); if (_showErrorsInToolbar && message->severityIsError()) { - qgcApp()->showToolBarMessage(message->getText()); + _app->showToolBarMessage(message->getText()); } } diff --git a/src/uas/UASMessageHandler.h b/src/uas/UASMessageHandler.h index cf05311cec29ac0188457a0890460fd2ac1108f9..163e4d32749a4122f7dc1518fda1e38e3136ed33 100644 --- a/src/uas/UASMessageHandler.h +++ b/src/uas/UASMessageHandler.h @@ -34,11 +34,12 @@ This file is part of the QGROUNDCONTROL project #include #include -#include "QGCSingleton.h" #include "Vehicle.h" +#include "QGCToolbox.h" class UASInterface; class UASMessageHandler; +class QGCApplication; /*! * @class UASMessage @@ -68,7 +69,7 @@ public: * @return true: This message is a of a severity which is considered an error */ bool severityIsError(); - + private: UASMessage(int componentid, int severity, QString text); void _setFormatedText(const QString formatedText) { _formatedText = formatedText; } @@ -78,14 +79,14 @@ private: QString _formatedText; }; -class UASMessageHandler : public QGCSingleton +class UASMessageHandler : public QGCTool { Q_OBJECT - DECLARE_QGC_SINGLETON(UASMessageHandler, UASMessageHandler) public: - explicit UASMessageHandler(QObject *parent = 0); + explicit UASMessageHandler(QGCApplication* app); ~UASMessageHandler(); + /** * @brief Locks access to the message list */ @@ -126,6 +127,9 @@ public: /// Begin to show message which are errors in the toolbar void showErrorsInToolbar(void) { _showErrorsInToolbar = true; } + // Override from QGCTool + virtual void setToolbox(QGCToolbox *toolbox); + public slots: /** * @brief Handle text message from current active UAS @@ -152,16 +156,16 @@ private slots: void _activeVehicleChanged(Vehicle* vehicle); private: - // Stores the UAS that we're currently receiving messages from. - UASInterface* _activeUAS; - QVector _messages; - QMutex _mutex; - int _errorCount; - int _errorCountTotal; - int _warningCount; - int _normalCount; - QString _latestError; - bool _showErrorsInToolbar; + UASInterface* _activeUAS; + QVector _messages; + QMutex _mutex; + int _errorCount; + int _errorCountTotal; + int _warningCount; + int _normalCount; + QString _latestError; + bool _showErrorsInToolbar; + MultiVehicleManager* _multiVehicleManager; }; #endif // QGCMESSAGEHANDLER_H diff --git a/src/ui/MAVLinkSettingsWidget.cc b/src/ui/MAVLinkSettingsWidget.cc index f013c13d383410ee3f97cc26fdc81ea6a2d3056b..e1d2f3305992f386f157028051880f0b227fd1eb 100644 --- a/src/ui/MAVLinkSettingsWidget.cc +++ b/src/ui/MAVLinkSettingsWidget.cc @@ -33,6 +33,7 @@ This file is part of the QGROUNDCONTROL project #include "MAVLinkSettingsWidget.h" #include "LinkManager.h" #include "UDPLink.h" +#include "QGCApplication.h" #include "ui_MAVLinkSettingsWidget.h" #include @@ -142,7 +143,7 @@ void MAVLinkSettingsWidget::enableDroneOS(bool enable) // Delete from all lists first UDPLink* firstUdp = NULL; - QList links = LinkManager::instance()->getLinks(); + QList links = qgcApp()->toolbox()->linkManager()->getLinks(); foreach (LinkInterface* link, links) { UDPLink* udp = dynamic_cast(link); diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 2ec5d95fc6acdfaea2acaaabd8f82a8729fa67ad..61db658279869d4e52098004df21d1368ea77769 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -210,8 +210,8 @@ MainWindow::MainWindow() #endif //QGC_MOUSE_ENABLED_LINUX // These also cause the screen to redraw so we need to update any OpenGL canvases in QML controls - connect(LinkManager::instance(), &LinkManager::linkConnected, this, &MainWindow::_linkStateChange); - connect(LinkManager::instance(), &LinkManager::linkDisconnected, this, &MainWindow::_linkStateChange); + connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkConnected, this, &MainWindow::_linkStateChange); + connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkDisconnected, this, &MainWindow::_linkStateChange); // Connect link if (_autoReconnect) @@ -323,7 +323,7 @@ void MainWindow::_buildCommonWidgets(void) { // Add generic MAVLink decoder // TODO: This is never deleted - mavlinkDecoder = new MAVLinkDecoder(MAVLinkProtocol::instance(), this); + mavlinkDecoder = new MAVLinkDecoder(qgcApp()->toolbox()->mavlinkProtocol(), this); connect(mavlinkDecoder, SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)), this, SIGNAL(valueChanged(int,QString,QString,QVariant,quint64))); @@ -372,7 +372,7 @@ void MainWindow::_createInnerDockWidget(const QString& widgetName) switch(action->data().toInt()) { case MAVLINK_INSPECTOR: - widget = new QGCMAVLinkInspector(widgetName, action, MAVLinkProtocol::instance(),this); + widget = new QGCMAVLinkInspector(widgetName, action, qgcApp()->toolbox()->mavlinkProtocol(),this); break; case CUSTOM_COMMAND: widget = new CustomCommandWidget(widgetName, action, this); @@ -438,7 +438,7 @@ void MainWindow::showStatusBarCallback(bool checked) void MainWindow::closeEvent(QCloseEvent *event) { // Disallow window close if there are active connections - if (LinkManager::instance()->anyConnectedLinks()) { + if (qgcApp()->toolbox()->linkManager()->anyConnectedLinks()) { QGCMessageBox::StandardButton button = QGCMessageBox::warning( tr("QGroundControl close"), @@ -446,7 +446,7 @@ void MainWindow::closeEvent(QCloseEvent *event) QMessageBox::Yes | QMessageBox::Cancel, QMessageBox::Cancel); if (button == QMessageBox::Yes) { - LinkManager::instance()->disconnectAll(); + qgcApp()->toolbox()->linkManager()->disconnectAll(); // The above disconnect causes a flurry of activity as the vehicle components are removed. This in turn // causes the Windows Version of Qt to crash if you allow the close event to be accepted. In order to prevent // the crash, we ignore the close event and setup a delayed timer to close the window after things settle down. @@ -461,7 +461,7 @@ void MainWindow::closeEvent(QCloseEvent *event) qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents); // Should not be any active connections - Q_ASSERT(!LinkManager::instance()->anyConnectedLinks()); + Q_ASSERT(!qgcApp()->toolbox()->linkManager()->anyConnectedLinks()); // We have to pull out the QmlWidget from the main window and delete it here, before // the MainWindow ends up getting deleted. Otherwise the Qml has a reference to MainWindow @@ -472,7 +472,11 @@ void MainWindow::closeEvent(QCloseEvent *event) _storeCurrentViewState(); storeSettings(); + event->accept(); + + _instance = NULL; + emit mainWindowClosed(); } void MainWindow::loadSettings() @@ -542,9 +546,9 @@ void MainWindow::connectCommonActions() connect(_ui.actionAdd_Link, SIGNAL(triggered()), this, SLOT(manageLinks())); // Audio output - _ui.actionMuteAudioOutput->setChecked(GAudioOutput::instance()->isMuted()); - connect(GAudioOutput::instance(), SIGNAL(mutedChanged(bool)), _ui.actionMuteAudioOutput, SLOT(setChecked(bool))); - connect(_ui.actionMuteAudioOutput, SIGNAL(triggered(bool)), GAudioOutput::instance(), SLOT(mute(bool))); + _ui.actionMuteAudioOutput->setChecked(qgcApp()->toolbox()->audioOutput()->isMuted()); + connect(qgcApp()->toolbox()->audioOutput(), SIGNAL(mutedChanged(bool)), _ui.actionMuteAudioOutput, SLOT(setChecked(bool))); + connect(_ui.actionMuteAudioOutput, SIGNAL(triggered(bool)), qgcApp()->toolbox()->audioOutput(), SLOT(mute(bool))); // Application Settings connect(_ui.actionSettings, SIGNAL(triggered()), this, SLOT(showSettings())); @@ -555,7 +559,7 @@ void MainWindow::connectCommonActions() connect(_ui.actionSetup, &QAction::triggered, this, &MainWindow::showSetupView); // Connect internal actions - connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleAdded, this, &MainWindow::_vehicleAdded); + connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleAdded, this, &MainWindow::_vehicleAdded); } void MainWindow::_openUrl(const QString& url, const QString& errorMessage) @@ -570,7 +574,7 @@ void MainWindow::_openUrl(const QString& url, const QString& errorMessage) void MainWindow::showSettings() { - SettingsDialog settings(this); + SettingsDialog settings(qgcApp()->toolbox()->audioOutput(), qgcApp()->toolbox()->flightMapSettings(), this); settings.exec(); } @@ -593,7 +597,7 @@ void MainWindow::_storeCurrentViewState(void) void MainWindow::manageLinks() { - SettingsDialog settings(this, SettingsDialog::ShowCommLinks); + SettingsDialog settings(qgcApp()->toolbox()->audioOutput(), qgcApp()->toolbox()->flightMapSettings(), this, SettingsDialog::ShowCommLinks); settings.exec(); } @@ -619,7 +623,7 @@ void MainWindow::restoreLastUsedConnection() if(settings.contains(key)) { QString connection = settings.value(key).toString(); // Create a link for it - LinkManager::instance()->createConnectedLink(connection); + qgcApp()->toolbox()->linkManager()->createConnectedLink(connection); } } diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index 6f8c9cba95cfa7263675a3ff114daedee5551d7c..fb9afe8f2274f88b4c3a877dfc3cdf444fc1260d 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -154,6 +154,9 @@ signals: /** Emitted when any the Canvas elements within QML wudgets need updating */ void repaintCanvas(); + // Used for unit tests to know when the main window closes + void mainWindowClosed(void); + #ifdef QGC_MOUSE_ENABLED_LINUX /** @brief Forward X11Event to catch 3DMouse inputs */ void x11EventOccured(XEvent *event); diff --git a/src/ui/MultiVehicleDockWidget.cc b/src/ui/MultiVehicleDockWidget.cc index 4c5d812ba65a466492461068fdc564e79e106348..e0a7e9be1c329007000bdc40e321c1ffce9bb084 100644 --- a/src/ui/MultiVehicleDockWidget.cc +++ b/src/ui/MultiVehicleDockWidget.cc @@ -24,6 +24,7 @@ #include "MultiVehicleDockWidget.h" #include "ui_MultiVehicleDockWidget.h" #include "MultiVehicleManager.h" +#include "QGCApplication.h" MultiVehicleDockWidget::MultiVehicleDockWidget(const QString& title, QAction* action, QWidget *parent) : QGCDockWidget(title, action, parent) @@ -33,19 +34,19 @@ MultiVehicleDockWidget::MultiVehicleDockWidget(const QString& title, QAction* ac setWindowTitle(title); - connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &MultiVehicleDockWidget::_activeVehicleChanged); - connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleAdded, this, &MultiVehicleDockWidget::_vehicleAdded); - connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleRemoved, this, &MultiVehicleDockWidget::_vehicleRemoved); + connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &MultiVehicleDockWidget::_activeVehicleChanged); + connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleAdded, this, &MultiVehicleDockWidget::_vehicleAdded); + connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleRemoved, this, &MultiVehicleDockWidget::_vehicleRemoved); } void MultiVehicleDockWidget::init(void) { - foreach (Vehicle* vehicle, MultiVehicleManager::instance()->vehicles()) { + foreach (Vehicle* vehicle, qgcApp()->toolbox()->multiVehicleManager()->vehicles()) { _vehicleAdded(vehicle); } - if (MultiVehicleManager::instance()->activeVehicle()) { - _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle()); + if (qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()) { + _activeVehicleChanged(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()); } } diff --git a/src/ui/QGCLinkConfiguration.cc b/src/ui/QGCLinkConfiguration.cc index 57c77d575d619b2822407b8641717f3a33110fb8..80ae6e9ec168da61c2499efc2f862519cd63e6f0 100644 --- a/src/ui/QGCLinkConfiguration.cc +++ b/src/ui/QGCLinkConfiguration.cc @@ -38,7 +38,7 @@ QGCLinkConfiguration::QGCLinkConfiguration(QWidget *parent) : _ui(new Ui::QGCLinkConfiguration) { // Stop automatic link updates while this UI is up - LinkManager::instance()->suspendConfigurationUpdates(true); + qgcApp()->toolbox()->linkManager()->suspendConfigurationUpdates(true); _ui->setupUi(this); _viewModel = new LinkViewModel; _ui->linkView->setModel(_viewModel); @@ -52,7 +52,7 @@ QGCLinkConfiguration::~QGCLinkConfiguration() if(_viewModel) delete _viewModel; if(_ui) delete _ui; // Resume automatic link updates - LinkManager::instance()->suspendConfigurationUpdates(false); + qgcApp()->toolbox()->linkManager()->suspendConfigurationUpdates(false); } void QGCLinkConfiguration::on_delLinkButton_clicked() @@ -72,13 +72,13 @@ void QGCLinkConfiguration::on_delLinkButton_clicked() LinkInterface* iface = config->getLink(); if(iface) { // Disconnect it (if connected) - LinkManager::instance()->disconnectLink(iface); + qgcApp()->toolbox()->linkManager()->disconnectLink(iface); } _viewModel->beginChange(); // Remove configuration - LinkManager::instance()->removeLinkConfiguration(config); + qgcApp()->toolbox()->linkManager()->removeLinkConfiguration(config); // Save list - LinkManager::instance()->saveLinkConfigurationList(); + qgcApp()->toolbox()->linkManager()->saveLinkConfigurationList(); _viewModel->endChange(); } } @@ -101,10 +101,10 @@ void QGCLinkConfiguration::on_connectLinkButton_clicked() if(link) { // Disconnect Link if (link->isConnected()) { - LinkManager::instance()->disconnectLink(link); + qgcApp()->toolbox()->linkManager()->disconnectLink(link); } } else { - LinkInterface* link = LinkManager::instance()->createConnectedLink(config); + LinkInterface* link = qgcApp()->toolbox()->linkManager()->createConnectedLink(config); if(link) { // Now go hunting for the parent so we can shut this down QWidget* pQw = parentWidget(); @@ -186,8 +186,8 @@ void QGCLinkConfiguration::on_addLinkButton_clicked() if(config) { _fixUnnamed(config); _viewModel->beginChange(); - LinkManager::instance()->addLinkConfiguration(commDialog->getConfig()); - LinkManager::instance()->saveLinkConfigurationList(); + qgcApp()->toolbox()->linkManager()->addLinkConfiguration(commDialog->getConfig()); + qgcApp()->toolbox()->linkManager()->saveLinkConfigurationList(); _viewModel->endChange(); } } @@ -213,7 +213,7 @@ void QGCLinkConfiguration::_editLink(int row) _viewModel->beginChange(); config->copyFrom(tmpConfig); // Save it - LinkManager::instance()->saveLinkConfigurationList(); + qgcApp()->toolbox()->linkManager()->saveLinkConfigurationList(); _viewModel->endChange(); // Tell link about changes (if any) config->updateSettings(); @@ -261,14 +261,14 @@ LinkViewModel::LinkViewModel(QObject *parent) : QAbstractListModel(parent) int LinkViewModel::rowCount( const QModelIndex & parent) const { Q_UNUSED(parent); - QList cfgList = LinkManager::instance()->getLinkConfigurationList(); + QList cfgList = qgcApp()->toolbox()->linkManager()->getLinkConfigurationList(); int count = cfgList.count(); return count; } QVariant LinkViewModel::data( const QModelIndex & index, int role) const { - QList cfgList = LinkManager::instance()->getLinkConfigurationList(); + QList cfgList = qgcApp()->toolbox()->linkManager()->getLinkConfigurationList(); if (role == Qt::DisplayRole && index.row() < cfgList.count()) { QString name(cfgList.at(index.row())->name()); return name; @@ -278,7 +278,7 @@ QVariant LinkViewModel::data( const QModelIndex & index, int role) const LinkConfiguration* LinkViewModel::getConfiguration(int row) { - QList cfgList = LinkManager::instance()->getLinkConfigurationList(); + QList cfgList = qgcApp()->toolbox()->linkManager()->getLinkConfigurationList(); if(row < cfgList.count()) { return cfgList.at(row); } diff --git a/src/ui/QGCMAVLinkInspector.cc b/src/ui/QGCMAVLinkInspector.cc index 2f1616301a1e5c946353573b0d77d059b7d40101..41a665d46d38e15eb8464dbada8fefc1401a88f3 100644 --- a/src/ui/QGCMAVLinkInspector.cc +++ b/src/ui/QGCMAVLinkInspector.cc @@ -4,6 +4,7 @@ #include "QGCMAVLinkInspector.h" #include "MultiVehicleManager.h" #include "UAS.h" +#include "QGCApplication.h" #include "ui_QGCMAVLinkInspector.h" @@ -52,7 +53,7 @@ QGCMAVLinkInspector::QGCMAVLinkInspector(const QString& title, QAction* action, connect(ui->clearButton, SIGNAL(clicked()), this, SLOT(clearView())); // Connect external connections - connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleAdded, this, &QGCMAVLinkInspector::_vehicleAdded); + connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleAdded, this, &QGCMAVLinkInspector::_vehicleAdded); connect(protocol, SIGNAL(messageReceived(LinkInterface*,mavlink_message_t)), this, SLOT(receiveMessage(LinkInterface*,mavlink_message_t))); // Attach the UI's refresh rate to a timer. @@ -101,7 +102,7 @@ void QGCMAVLinkInspector::rebuildComponentList() ui->componentComboBox->addItem(tr("All"), 0); // Fill - Vehicle* vehicle = MultiVehicleManager::instance()->getVehicleById(selectedSystemID); + Vehicle* vehicle = qgcApp()->toolbox()->multiVehicleManager()->getVehicleById(selectedSystemID); if (vehicle) { UASInterface* uas = vehicle->uas(); @@ -334,7 +335,7 @@ void QGCMAVLinkInspector::addUAStoTree(int sysId) if(!uasTreeWidgetItems.contains(sysId)) { // Add the UAS to the main tree after it has been created - Vehicle* vehicle = MultiVehicleManager::instance()->getVehicleById(sysId); + Vehicle* vehicle = qgcApp()->toolbox()->multiVehicleManager()->getVehicleById(sysId); if (vehicle) { UASInterface* uas = vehicle->uas(); diff --git a/src/ui/QGCMAVLinkLogPlayer.cc b/src/ui/QGCMAVLinkLogPlayer.cc index eaf7d5f11ded2ca8b0f3fa2f6bccd11b50c4667d..957a2e363ffb30e099b163fe9c7bbd45d393c13b 100644 --- a/src/ui/QGCMAVLinkLogPlayer.cc +++ b/src/ui/QGCMAVLinkLogPlayer.cc @@ -60,7 +60,7 @@ void QGCMAVLinkLogPlayer::_pause(void) void QGCMAVLinkLogPlayer::_selectLogFileForPlayback(void) { // Disallow replay when any links are connected - if (LinkManager::instance()->anyConnectedLinks()) { + if (qgcApp()->toolbox()->linkManager()->anyConnectedLinks()) { QGCMessageBox::information(tr("Log Replay"), tr("You must close all connections prior to replaying a log.")); return; } @@ -81,7 +81,7 @@ void QGCMAVLinkLogPlayer::_selectLogFileForPlayback(void) linkConfig->setLogFilename(logFilename); linkConfig->setName(linkConfig->logFilenameShort()); _ui->logFileNameLabel->setText(linkConfig->logFilenameShort()); - _replayLink = (LogReplayLink*)LinkManager::instance()->createConnectedLink(linkConfig); + _replayLink = (LogReplayLink*)qgcApp()->toolbox()->linkManager()->createConnectedLink(linkConfig); connect(_replayLink, &LogReplayLink::logFileStats, this, &QGCMAVLinkLogPlayer::_logFileStats); connect(_replayLink, &LogReplayLink::playbackStarted, this, &QGCMAVLinkLogPlayer::_playbackStarted); diff --git a/src/ui/QGCMapRCToParamDialog.cpp b/src/ui/QGCMapRCToParamDialog.cpp index 19c79201101d8e97c58d99f82a4efd369d915f95..e3a2dfff1c4560a64b775e8c6f53839ae6e317f3 100644 --- a/src/ui/QGCMapRCToParamDialog.cpp +++ b/src/ui/QGCMapRCToParamDialog.cpp @@ -26,7 +26,6 @@ #include "QGCMapRCToParamDialog.h" #include "ui_QGCMapRCToParamDialog.h" -#include "MultiVehicleManager.h" #include #include @@ -34,11 +33,12 @@ #include #include -QGCMapRCToParamDialog::QGCMapRCToParamDialog(QString param_id, UASInterface *mav, QWidget *parent) : - QDialog(parent), - param_id(param_id), - mav(mav), - ui(new Ui::QGCMapRCToParamDialog) +QGCMapRCToParamDialog::QGCMapRCToParamDialog(QString param_id, UASInterface *mav, MultiVehicleManager* multiVehicleManager, QWidget *parent) + : QDialog(parent) + , param_id(param_id) + , mav(mav) + , _multiVehicleManager(multiVehicleManager) + , ui(new Ui::QGCMapRCToParamDialog) { ui->setupUi(this); @@ -49,7 +49,7 @@ QGCMapRCToParamDialog::QGCMapRCToParamDialog(QString param_id, UASInterface *mav ui->paramIdLabel->setText(param_id); // refresh the parameter from onboard to make sure the current value is used - AutoPilotPlugin* autopilot = MultiVehicleManager::instance()->getVehicleById(mav->getUASID())->autopilotPlugin(); + AutoPilotPlugin* autopilot = _multiVehicleManager->getVehicleById(mav->getUASID())->autopilotPlugin(); Q_ASSERT(autopilot); connect(autopilot->getParameterFact(FactSystem::defaultComponentId, param_id), &Fact::valueChanged, this, &QGCMapRCToParamDialog::_parameterUpdated); autopilot->refreshParameter(FactSystem::defaultComponentId, param_id); diff --git a/src/ui/QGCMapRCToParamDialog.h b/src/ui/QGCMapRCToParamDialog.h index cc0f2d3c049bc96b1f1ff2501e65dd78d36f6f68..0460b764d81741ff67ff3e0edc31999f35935d89 100644 --- a/src/ui/QGCMapRCToParamDialog.h +++ b/src/ui/QGCMapRCToParamDialog.h @@ -33,6 +33,7 @@ #include "UASInterface.h" #include "AutoPilotPlugin.h" +#include "MultiVehicleManager.h" namespace Ui { class QGCMapRCToParamDialog; @@ -46,7 +47,7 @@ class QGCMapRCToParamDialog : public QDialog QThread paramLoadThread; public: - explicit QGCMapRCToParamDialog(QString param_id, UASInterface *mav, QWidget *parent = 0); + explicit QGCMapRCToParamDialog(QString param_id, UASInterface *mav, MultiVehicleManager* multiVehicleManager, QWidget *parent = 0); ~QGCMapRCToParamDialog(); signals: @@ -65,7 +66,8 @@ private slots: void _parameterUpdated(QVariant value); private: - Ui::QGCMapRCToParamDialog *ui; + MultiVehicleManager* _multiVehicleManager; + Ui::QGCMapRCToParamDialog* ui; }; #endif // QGCMAPRCTOPARAMDIALOG_H diff --git a/src/ui/QGCTabbedInfoView.cpp b/src/ui/QGCTabbedInfoView.cpp index 0b06f4a07b643a55c7823a765a1c34b8e2af7f20..21b652c3cac26bfee6bdb26e340cf9e2c0aa8de5 100644 --- a/src/ui/QGCTabbedInfoView.cpp +++ b/src/ui/QGCTabbedInfoView.cpp @@ -1,10 +1,11 @@ #include "QGCTabbedInfoView.h" +#include "QGCApplication.h" QGCTabbedInfoView::QGCTabbedInfoView(const QString& title, QAction* action, QWidget *parent) : QGCDockWidget(title, action, parent) { ui.setupUi(this); - messageView = new UASMessageViewWidget(this); + messageView = new UASMessageViewWidget(qgcApp()->toolbox()->uasMessageHandler(), this); //actionsWidget = new UASActionsWidget(this); quickView = new UASQuickView(this); //rawView = new UASRawStatusView(this); diff --git a/src/ui/QGCUASFileViewMulti.cc b/src/ui/QGCUASFileViewMulti.cc index 3455d3e60eb4cbfd7bfaa361c098ed34687669ad..ace27c6888d6beef35584e3f8599bfd81134ed2a 100644 --- a/src/ui/QGCUASFileViewMulti.cc +++ b/src/ui/QGCUASFileViewMulti.cc @@ -3,6 +3,7 @@ #include "UASInterface.h" #include "MultiVehicleManager.h" #include "QGCUASFileView.h" +#include "QGCApplication.h" QGCUASFileViewMulti::QGCUASFileViewMulti(const QString& title, QAction* action, QWidget *parent) : QGCDockWidget(title, action, parent), @@ -10,13 +11,13 @@ QGCUASFileViewMulti::QGCUASFileViewMulti(const QString& title, QAction* action, { ui->setupUi(this); setMinimumSize(600, 80); - connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &QGCUASFileViewMulti::_activeVehicleChanged); - connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleAdded, this, &QGCUASFileViewMulti::_vehicleAdded); - connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleRemoved, this, &QGCUASFileViewMulti::_vehicleRemoved); + connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &QGCUASFileViewMulti::_activeVehicleChanged); + connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleAdded, this, &QGCUASFileViewMulti::_vehicleAdded); + connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleRemoved, this, &QGCUASFileViewMulti::_vehicleRemoved); - if (MultiVehicleManager::instance()->activeVehicle()) { - _vehicleAdded(MultiVehicleManager::instance()->activeVehicle()); - _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle()); + if (qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()) { + _vehicleAdded(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()); + _activeVehicleChanged(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()); } loadSettings(); diff --git a/src/ui/SettingsDialog.cc b/src/ui/SettingsDialog.cc index ac5f6dbbb5e528cbeb017ceeb49ba5e077cdc0ab..f6a8db6770ed20a9c2eb6ed0f8f418660c146fa7 100644 --- a/src/ui/SettingsDialog.cc +++ b/src/ui/SettingsDialog.cc @@ -39,10 +39,12 @@ #include "MainToolBarController.h" #include "FlightMapSettings.h" -SettingsDialog::SettingsDialog(QWidget *parent, int showTab, Qt::WindowFlags flags) : -QDialog(parent, flags), -_mainWindow(MainWindow::instance()), -_ui(new Ui::SettingsDialog) +SettingsDialog::SettingsDialog(GAudioOutput* audioOutput, FlightMapSettings* flightMapSettings, QWidget *parent, int showTab, Qt::WindowFlags flags) + : QDialog(parent, flags) + , _mainWindow(MainWindow::instance()) + , _audioOutput(audioOutput) + , _flightMapSettings(flightMapSettings) + , _ui(new Ui::SettingsDialog) { _ui->setupUi(this); @@ -55,7 +57,7 @@ _ui(new Ui::SettingsDialog) move(position.topLeft()); QGCLinkConfiguration* pLinkConf = new QGCLinkConfiguration(this); - MAVLinkSettingsWidget* pMavsettings = new MAVLinkSettingsWidget(MAVLinkProtocol::instance(), this); + MAVLinkSettingsWidget* pMavsettings = new MAVLinkSettingsWidget(qgcApp()->toolbox()->mavlinkProtocol(), this); // Add the link settings pane _ui->tabWidget->addTab(pLinkConf, "Comm Links"); @@ -65,9 +67,9 @@ _ui(new Ui::SettingsDialog) this->window()->setWindowTitle(tr("QGroundControl Settings")); // Audio preferences - _ui->audioMuteCheckBox->setChecked(GAudioOutput::instance()->isMuted()); - connect(_ui->audioMuteCheckBox, SIGNAL(toggled(bool)), GAudioOutput::instance(), SLOT(mute(bool))); - connect(GAudioOutput::instance(), SIGNAL(mutedChanged(bool)), _ui->audioMuteCheckBox, SLOT(setChecked(bool))); + _ui->audioMuteCheckBox->setChecked(_audioOutput->isMuted()); + connect(_ui->audioMuteCheckBox, SIGNAL(toggled(bool)), _audioOutput, SLOT(mute(bool))); + connect(_audioOutput, SIGNAL(mutedChanged(bool)), _ui->audioMuteCheckBox, SLOT(setChecked(bool))); // Reconnect _ui->reconnectCheckBox->setChecked(_mainWindow->autoReconnectEnabled()); @@ -92,7 +94,7 @@ _ui(new Ui::SettingsDialog) // Flight Map settings - FlightMapSettings* fmSettings = FlightMapSettings::instance(); + FlightMapSettings* fmSettings = _flightMapSettings; _ui->bingMapRadio->setChecked(fmSettings->mapProvider() == "Bing"); _ui->googleMapRadio->setChecked(fmSettings->mapProvider() == "Google"); _ui->openMapRadio->setChecked(fmSettings->mapProvider() == "Open"); @@ -178,20 +180,20 @@ void SettingsDialog::_selectSavedFilesDirectory(void) void SettingsDialog::_bingMapRadioClicked(bool checked) { if (checked) { - FlightMapSettings::instance()->setMapProvider("Bing"); + _flightMapSettings->setMapProvider("Bing"); } } void SettingsDialog::_googleMapRadioClicked(bool checked) { if (checked) { - FlightMapSettings::instance()->setMapProvider("Google"); + _flightMapSettings->setMapProvider("Google"); } } void SettingsDialog::_openMapRadioClicked(bool checked) { if (checked) { - FlightMapSettings::instance()->setMapProvider("Open"); + _flightMapSettings->setMapProvider("Open"); } } diff --git a/src/ui/SettingsDialog.h b/src/ui/SettingsDialog.h index d9dc838578ccf5890e142a36647aa2fa5275e15e..6878cff62941748c2e6c036111d036d04463a43c 100644 --- a/src/ui/SettingsDialog.h +++ b/src/ui/SettingsDialog.h @@ -25,7 +25,10 @@ #define SETTINGSDIALOG_H #include + #include "MainWindow.h" +#include "GAudioOutput.h" +#include "FlightMapSettings.h" namespace Ui { @@ -45,7 +48,7 @@ public: ShowMavlink }; - SettingsDialog(QWidget *parent = 0, int showTab = ShowDefault, Qt::WindowFlags flags = Qt::Sheet); + SettingsDialog(GAudioOutput* audioOuput, FlightMapSettings* flightMapSettings, QWidget *parent = 0, int showTab = ShowDefault, Qt::WindowFlags flags = Qt::Sheet); ~SettingsDialog(); public slots: @@ -62,6 +65,8 @@ private slots: private: MainWindow* _mainWindow; + GAudioOutput* _audioOutput; + FlightMapSettings* _flightMapSettings; Ui::SettingsDialog* _ui; }; diff --git a/src/ui/toolbar/MainToolBarController.cc b/src/ui/toolbar/MainToolBarController.cc index dc8242f919be5e0cc7922dd02a32b680a9f07db8..900e490670e5c3ddd74d65d98be7be76dafba20a 100644 --- a/src/ui/toolbar/MainToolBarController.cc +++ b/src/ui/toolbar/MainToolBarController.cc @@ -54,19 +54,19 @@ MainToolBarController::MainToolBarController(QObject* parent) { emit configListChanged(); emit connectionCountChanged(_connectionCount); - _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle()); + _activeVehicleChanged(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()); // Link signals - connect(LinkManager::instance(), &LinkManager::linkConfigurationChanged, this, &MainToolBarController::_updateConfigurations); - connect(LinkManager::instance(), &LinkManager::linkConnected, this, &MainToolBarController::_linkConnected); - connect(LinkManager::instance(), &LinkManager::linkDisconnected, this, &MainToolBarController::_linkDisconnected); + connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkConfigurationChanged, this, &MainToolBarController::_updateConfigurations); + connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkConnected, this, &MainToolBarController::_linkConnected); + connect(qgcApp()->toolbox()->linkManager(), &LinkManager::linkDisconnected, this, &MainToolBarController::_linkDisconnected); // RSSI (didn't like standard connection) - connect(MAVLinkProtocol::instance(), + connect(qgcApp()->toolbox()->mavlinkProtocol(), SIGNAL(radioStatusChanged(LinkInterface*, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned)), this, SLOT(_telemetryChanged(LinkInterface*, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned))); - connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &MainToolBarController::_activeVehicleChanged); + connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &MainToolBarController::_activeVehicleChanged); } MainToolBarController::~MainToolBarController() @@ -95,7 +95,7 @@ void MainToolBarController::onDisconnect(QString conf) // Disconnect Only Connected Link int connectedCount = 0; LinkInterface* connectedLink = NULL; - QList links = LinkManager::instance()->getLinks(); + QList links = qgcApp()->toolbox()->linkManager()->getLinks(); foreach(LinkInterface* link, links) { if (link->isConnected()) { connectedCount++; @@ -105,14 +105,14 @@ void MainToolBarController::onDisconnect(QString conf) Q_ASSERT(connectedCount == 1); Q_ASSERT(_connectionCount == 1); Q_ASSERT(connectedLink); - LinkManager::instance()->disconnectLink(connectedLink); + qgcApp()->toolbox()->linkManager()->disconnectLink(connectedLink); } else { // Disconnect Named Connected Link - QList links = LinkManager::instance()->getLinks(); + QList links = qgcApp()->toolbox()->linkManager()->getLinks(); foreach(LinkInterface* link, links) { if (link->isConnected()) { if(link->getLinkConfiguration() && link->getLinkConfiguration()->name() == conf) { - LinkManager::instance()->disconnectLink(link); + qgcApp()->toolbox()->linkManager()->disconnectLink(link); } } } @@ -126,14 +126,14 @@ void MainToolBarController::onConnect(QString conf) MainWindow::instance()->manageLinks(); } else { // We don't want the list updating under our feet - LinkManager::instance()->suspendConfigurationUpdates(true); + qgcApp()->toolbox()->linkManager()->suspendConfigurationUpdates(true); // Create a link - LinkInterface* link = LinkManager::instance()->createConnectedLink(conf); + LinkInterface* link = qgcApp()->toolbox()->linkManager()->createConnectedLink(conf); if(link) { // Save last used connection MainWindow::instance()->saveLastUsedConnection(conf); } - LinkManager::instance()->suspendConfigurationUpdates(false); + qgcApp()->toolbox()->linkManager()->suspendConfigurationUpdates(false); } } @@ -143,9 +143,9 @@ void MainToolBarController::onEnterMessageArea(int x, int y) Q_UNUSED(y); // If not already there and messages are actually present - if(!_rollDownMessages && UASMessageHandler::instance()->messages().count()) { - if (MultiVehicleManager::instance()->activeVehicle()) { - MultiVehicleManager::instance()->activeVehicle()->resetMessages(); + if(!_rollDownMessages && qgcApp()->toolbox()->uasMessageHandler()->messages().count()) { + if (qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()) { + qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->resetMessages(); } // FIXME: Position of the message dropdown is hacked right now to speed up Qml conversion @@ -158,7 +158,7 @@ void MainToolBarController::onEnterMessageArea(int x, int y) #endif // Put dialog on top of the message alert icon - _rollDownMessages = new UASMessageViewRollDown(MainWindow::instance()); + _rollDownMessages = new UASMessageViewRollDown(qgcApp()->toolbox()->uasMessageHandler(), MainWindow::instance()); _rollDownMessages->setAttribute(Qt::WA_DeleteOnClose); _rollDownMessages->move(QPoint(100, 100)); _rollDownMessages->setMinimumSize(dialogWidth,200); @@ -196,7 +196,7 @@ void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle) void MainToolBarController::_updateConfigurations() { QStringList tmpList; - QList configs = LinkManager::instance()->getLinkConfigurationList(); + QList configs = qgcApp()->toolbox()->linkManager()->getLinkConfigurationList(); foreach(LinkConfiguration* conf, configs) { if(conf) { if(conf->isPreferred()) { @@ -263,7 +263,7 @@ void MainToolBarController::_updateConnection(LinkInterface *disconnectedLink) int oldCount = _connectionCount; // If there are multiple connected links add/update the connect button menu _connectionCount = 0; - QList links = LinkManager::instance()->getLinks(); + QList links = qgcApp()->toolbox()->linkManager()->getLinks(); foreach(LinkInterface* link, links) { if (disconnectedLink != link && link->isConnected()) { _connectionCount++; diff --git a/src/ui/uas/UASInfoWidget.cc b/src/ui/uas/UASInfoWidget.cc index c9f06d6af5a78237b1c039f86e108b8f70b4faf1..9011543fe0044ce05c4f87427fd4126319da4d1d 100644 --- a/src/ui/uas/UASInfoWidget.cc +++ b/src/ui/uas/UASInfoWidget.cc @@ -42,6 +42,7 @@ This file is part of the PIXHAWK project #include "MultiVehicleManager.h" #include "QGC.h" #include "UAS.h" +#include "QGCApplication.h" UASInfoWidget::UASInfoWidget(const QString& title, QAction* action, QWidget *parent, QString name) : QGCDockWidget(title, action, parent) @@ -50,8 +51,8 @@ UASInfoWidget::UASInfoWidget(const QString& title, QAction* action, QWidget *par this->name = name; activeUAS = NULL; - connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &UASInfoWidget::_activeVehicleChanged); - _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle()); + connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &UASInfoWidget::_activeVehicleChanged); + _activeVehicleChanged(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()); startTime = QGC::groundTimeMilliseconds(); diff --git a/src/ui/uas/UASMessageView.cc b/src/ui/uas/UASMessageView.cc index 4e001c4c466921e2c8ac11476c9021ae22c9de0e..114153edffb6cc436b12da89d18350b19482aeb5 100644 --- a/src/ui/uas/UASMessageView.cc +++ b/src/ui/uas/UASMessageView.cc @@ -26,7 +26,6 @@ This file is part of the QGROUNDCONTROL project #include "UASMessageView.h" #include "QGCUnconnectedInfoWidget.h" -#include "UASMessageHandler.h" #include "ui_UASMessageView.h" /*------------------------------------------------------------------------------------- @@ -49,9 +48,10 @@ UASMessageView::~UASMessageView() UASMessageViewWidget -------------------------------------------------------------------------------------*/ -UASMessageViewWidget::UASMessageViewWidget(QWidget *parent) +UASMessageViewWidget::UASMessageViewWidget(UASMessageHandler* uasMessageHandler, QWidget *parent) : UASMessageView(parent) , _unconnectedWidget(NULL) + , _uasMessageHandler(uasMessageHandler) { setStyleSheet("QPlainTextEdit { border: 0px }"); // Construct initial widget @@ -66,7 +66,7 @@ UASMessageViewWidget::UASMessageViewWidget(QWidget *parent) connect(clearAction, &QAction::triggered, this, &UASMessageViewWidget::clearMessages); ui()->plainTextEdit->addAction(clearAction); // Connect message handler - connect(UASMessageHandler::instance(), &UASMessageHandler::textMessageReceived, this, &UASMessageViewWidget::handleTextMessage); + connect(_uasMessageHandler, &UASMessageHandler::textMessageReceived, this, &UASMessageViewWidget::handleTextMessage); } UASMessageViewWidget::~UASMessageViewWidget() @@ -77,7 +77,7 @@ UASMessageViewWidget::~UASMessageViewWidget() void UASMessageViewWidget::clearMessages() { ui()->plainTextEdit->clear(); - UASMessageHandler::instance()->clearMessages(); + _uasMessageHandler->clearMessages(); } void UASMessageViewWidget::handleTextMessage(UASMessage *message) @@ -110,24 +110,25 @@ void UASMessageViewWidget::handleTextMessage(UASMessage *message) UASMessageViewRollDown -------------------------------------------------------------------------------------*/ -UASMessageViewRollDown::UASMessageViewRollDown(QWidget *parent) +UASMessageViewRollDown::UASMessageViewRollDown(UASMessageHandler* uasMessageHandler, QWidget *parent) : UASMessageView(parent) + , _uasMessageHandler(uasMessageHandler) { setAttribute(Qt::WA_TranslucentBackground); setStyleSheet("background-color: rgba(0%,0%,0%,80%); border: 2px;"); QPlainTextEdit *msgWidget = ui()->plainTextEdit; // Init Messages - UASMessageHandler::instance()->lockAccess(); + _uasMessageHandler->lockAccess(); msgWidget->setUpdatesEnabled(false); - QVector messages = UASMessageHandler::instance()->messages(); + QVector messages = _uasMessageHandler->messages(); for(int i = 0; i < messages.count(); i++) { msgWidget->appendHtml(messages.at(i)->getFormatedText()); } QScrollBar *scroller = msgWidget->verticalScrollBar(); scroller->setValue(scroller->maximum()); msgWidget->setUpdatesEnabled(true); - connect(UASMessageHandler::instance(), &UASMessageHandler::textMessageReceived, this, &UASMessageViewRollDown::handleTextMessage); - UASMessageHandler::instance()->unlockAccess(); + connect(_uasMessageHandler, &UASMessageHandler::textMessageReceived, this, &UASMessageViewRollDown::handleTextMessage); + _uasMessageHandler->unlockAccess(); } UASMessageViewRollDown::~UASMessageViewRollDown() diff --git a/src/ui/uas/UASMessageView.h b/src/ui/uas/UASMessageView.h index 4cae37643059cb641cdc677f2300ac07d9e46ea2..5ef078b6c345abb2e118570b3f8b5ae1002c7cf8 100644 --- a/src/ui/uas/UASMessageView.h +++ b/src/ui/uas/UASMessageView.h @@ -28,7 +28,9 @@ This file is part of the QGROUNDCONTROL project #include #include #include + #include "QGCUnconnectedInfoWidget.h" +#include "UASMessageHandler.h" class UASMessage; @@ -45,6 +47,7 @@ public: explicit UASMessageView(QWidget *parent = 0); virtual ~UASMessageView(); Ui::UASMessageView* ui() { return _ui; } + private: Ui::UASMessageView* _ui; }; @@ -53,14 +56,18 @@ private: class UASMessageViewWidget : public UASMessageView { Q_OBJECT + public: - explicit UASMessageViewWidget(QWidget *parent = 0); + explicit UASMessageViewWidget(UASMessageHandler* uasMessageHandler, QWidget *parent = 0); ~UASMessageViewWidget(); + public slots: void handleTextMessage(UASMessage* message); void clearMessages(); + private: - QGCUnconnectedInfoWidget* _unconnectedWidget; + QGCUnconnectedInfoWidget* _unconnectedWidget; + UASMessageHandler* _uasMessageHandler; }; // Roll down Message View @@ -68,14 +75,20 @@ class UASMessageViewRollDown : public UASMessageView { Q_OBJECT public: - explicit UASMessageViewRollDown(QWidget *parent); + explicit UASMessageViewRollDown(UASMessageHandler* uasMessageHandler, QWidget *parent); ~UASMessageViewRollDown(); + signals: void closeWindow(); + public slots: void handleTextMessage(UASMessage* message); + protected: void leaveEvent(QEvent* event); + +private: + UASMessageHandler* _uasMessageHandler; }; #endif // QGCMESSAGEVIEW_H diff --git a/src/ui/uas/UASQuickView.cc b/src/ui/uas/UASQuickView.cc index 93e946f4e37a15992cd0dbb42b00941df7361eaf..96fa299028d394a10095a85519ff05ced6a683d9 100644 --- a/src/ui/uas/UASQuickView.cc +++ b/src/ui/uas/UASQuickView.cc @@ -3,6 +3,7 @@ #include "UASQuickViewTextItem.h" #include "MultiVehicleManager.h" #include "UAS.h" +#include "QGCApplication.h" #include #include @@ -21,8 +22,8 @@ UASQuickView::UASQuickView(QWidget *parent) : QWidget(parent), m_verticalLayoutList.append(new QVBoxLayout()); ui.horizontalLayout->addItem(m_verticalLayoutList[0]); - connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &UASQuickView::_activeVehicleChanged); - _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle()); + connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &UASQuickView::_activeVehicleChanged); + _activeVehicleChanged(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()); this->setContextMenuPolicy(Qt::ActionsContextMenu); loadSettings();