diff --git a/QGCApplication.pro b/QGCApplication.pro index 5b98331782ef57b43e3d66704de20728c8db3911..a89c6d8af0b236db64ad19f28576ad0d2433e7a6 100644 --- a/QGCApplication.pro +++ b/QGCApplication.pro @@ -527,14 +527,13 @@ HEADERS+= \ src/FirmwarePlugin/FirmwarePluginManager.h \ src/FirmwarePlugin/FirmwarePlugin.h \ src/FirmwarePlugin/APM/APMFirmwarePlugin.h \ - src/FirmwarePlugin/APM/APMParameterLoader.h \ + src/FirmwarePlugin/APM/APMParameterMetaData.h \ src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h \ src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h \ src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h \ src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h \ - src/FirmwarePlugin/Generic/GenericParameterLoader.h \ src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h \ - src/FirmwarePlugin/PX4/PX4ParameterLoader.h \ + src/FirmwarePlugin/PX4/PX4ParameterMetaData.h \ src/Vehicle/MultiVehicleManager.h \ src/Vehicle/Vehicle.h \ src/VehicleSetup/VehicleComponent.h \ @@ -568,15 +567,14 @@ SOURCES += \ src/AutoPilotPlugins/PX4/SensorsComponent.cc \ src/AutoPilotPlugins/PX4/SensorsComponentController.cc \ src/FirmwarePlugin/APM/APMFirmwarePlugin.cc \ - src/FirmwarePlugin/APM/APMParameterLoader.cc \ + src/FirmwarePlugin/APM/APMParameterMetaData.cc \ src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc \ src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc \ src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc \ src/FirmwarePlugin/FirmwarePluginManager.cc \ src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc \ - src/FirmwarePlugin/Generic/GenericParameterLoader.cc \ src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc \ - src/FirmwarePlugin/PX4/PX4ParameterLoader.cc \ + src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc \ src/Vehicle/MultiVehicleManager.cc \ src/Vehicle/Vehicle.cc \ src/VehicleSetup/VehicleComponent.cc \ diff --git a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc index 0eb799c7c0e6937360cf6efbaf89093284006591..09e5e1c8a537b04bd89d6ffde89a161f0ca21c79 100644 --- a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc @@ -25,7 +25,7 @@ #include "AutoPilotPluginManager.h" #include "QGCMessageBox.h" #include "UAS.h" -#include "FirmwarePlugin/APM/APMParameterLoader.h" // FIXME: Hack +#include "FirmwarePlugin/APM/APMParameterMetaData.h" // FIXME: Hack #include "FirmwarePlugin/APM/APMFirmwarePlugin.h" // FIXME: Hack /// This is the AutoPilotPlugin implementatin for the MAV_AUTOPILOT_ARDUPILOT type. @@ -34,9 +34,6 @@ APMAutoPilotPlugin::APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent) : _incorrectParameterVersion(false) { Q_ASSERT(vehicle); - - // This kicks off parameter load - _firmwarePlugin->getParameterLoader(this, vehicle); } APMAutoPilotPlugin::~APMAutoPilotPlugin() @@ -44,11 +41,6 @@ APMAutoPilotPlugin::~APMAutoPilotPlugin() } -void APMAutoPilotPlugin::clearStaticData(void) -{ - APMParameterLoader::clearStaticData(); -} - const QVariantList& APMAutoPilotPlugin::vehicleComponents(void) { static const QVariantList emptyList; diff --git a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h index 4ebacf88efc4c8d31e44cc6b139ecbee7909baff..3864d2c2bccb0dfcedf1d138f03bd314c6249d69 100644 --- a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h +++ b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h @@ -39,8 +39,6 @@ public: // Overrides from AutoPilotPlugin virtual const QVariantList& vehicleComponents(void); - static void clearStaticData(void); - public slots: // FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle void _parametersReadyPreChecks(bool missingParameters); diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.cc b/src/AutoPilotPlugins/AutoPilotPlugin.cc index eb2b9c723558145ba97a6c2a8c9999bcae7624c4..177212814e3495f4edb73c4e51e5eb7ee02e5657 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/AutoPilotPlugin.cc @@ -109,34 +109,34 @@ void AutoPilotPlugin::resetAllParametersToDefaults(void) void AutoPilotPlugin::refreshAllParameters(void) { - _firmwarePlugin->getParameterLoader(this, _vehicle)->refreshAllParameters(); + _vehicle->getParameterLoader()->refreshAllParameters(); } void AutoPilotPlugin::refreshParameter(int componentId, const QString& name) { - _firmwarePlugin->getParameterLoader(this, _vehicle)->refreshParameter(componentId, name); + _vehicle->getParameterLoader()->refreshParameter(componentId, name); } void AutoPilotPlugin::refreshParametersPrefix(int componentId, const QString& namePrefix) { - _firmwarePlugin->getParameterLoader(this, _vehicle)->refreshParametersPrefix(componentId, namePrefix); + _vehicle->getParameterLoader()->refreshParametersPrefix(componentId, namePrefix); } bool AutoPilotPlugin::parameterExists(int componentId, const QString& name) { - return _firmwarePlugin->getParameterLoader(this, _vehicle)->parameterExists(componentId, name); + return _vehicle->getParameterLoader()->parameterExists(componentId, name); } Fact* AutoPilotPlugin::getParameterFact(int componentId, const QString& name) { - return _firmwarePlugin->getParameterLoader(this, _vehicle)->getFact(componentId, name); + return _vehicle->getParameterLoader()->getFact(componentId, name); } bool AutoPilotPlugin::factExists(FactSystem::Provider_t provider, int componentId, const QString& name) { switch (provider) { case FactSystem::ParameterProvider: - return _firmwarePlugin->getParameterLoader(this, _vehicle)->parameterExists(componentId, name); + return _vehicle->getParameterLoader()->parameterExists(componentId, name); // Other providers will go here once they come online } @@ -149,7 +149,7 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId, { switch (provider) { case FactSystem::ParameterProvider: - return _firmwarePlugin->getParameterLoader(this, _vehicle)->getFact(componentId, name); + return _vehicle->getParameterLoader()->getFact(componentId, name); // Other providers will go here once they come online } @@ -160,20 +160,20 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId, QStringList AutoPilotPlugin::parameterNames(int componentId) { - return _firmwarePlugin->getParameterLoader(this, _vehicle)->parameterNames(componentId); + return _vehicle->getParameterLoader()->parameterNames(componentId); } const QMap >& AutoPilotPlugin::getGroupMap(void) { - return _firmwarePlugin->getParameterLoader(this, _vehicle)->getGroupMap(); + return _vehicle->getParameterLoader()->getGroupMap(); } void AutoPilotPlugin::writeParametersToStream(QTextStream &stream) { - _firmwarePlugin->getParameterLoader(this, _vehicle)->writeParametersToStream(stream, _vehicle->uas()->getUASName()); + _vehicle->getParameterLoader()->writeParametersToStream(stream, _vehicle->uas()->getUASName()); } QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream) { - return _firmwarePlugin->getParameterLoader(this, _vehicle)->readParametersFromStream(stream); + return _vehicle->getParameterLoader()->readParametersFromStream(stream); } diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.h b/src/AutoPilotPlugins/AutoPilotPlugin.h index 654d5aa2787761af86c8b29e4bc37f05e3d533ea..8e24bb5c6f82f508dca8e2380dcd84d36eca8fd1 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.h +++ b/src/AutoPilotPlugins/AutoPilotPlugin.h @@ -114,8 +114,6 @@ public: // Must be implemented by derived class virtual const QVariantList& vehicleComponents(void) = 0; - static void clearStaticData(void); - // Property accessors bool parametersReady(void) { return _parametersReady; } bool missingParameters(void) { return _missingParameters; } diff --git a/src/AutoPilotPlugins/AutoPilotPluginManager.cc b/src/AutoPilotPlugins/AutoPilotPluginManager.cc index 88435dfc8588c30d9730fea3199009ef27a0de86..7220fa11e81780ab5c1086d1dc913b6e744e6a68 100644 --- a/src/AutoPilotPlugins/AutoPilotPluginManager.cc +++ b/src/AutoPilotPlugins/AutoPilotPluginManager.cc @@ -37,12 +37,6 @@ AutoPilotPluginManager::AutoPilotPluginManager(QObject* parent) : } -AutoPilotPluginManager::~AutoPilotPluginManager() -{ - PX4AutoPilotPlugin::clearStaticData(); - GenericAutoPilotPlugin::clearStaticData(); -} - AutoPilotPlugin* AutoPilotPluginManager::newAutopilotPluginForVehicle(Vehicle* vehicle) { switch (vehicle->firmwareType()) { diff --git a/src/AutoPilotPlugins/AutoPilotPluginManager.h b/src/AutoPilotPlugins/AutoPilotPluginManager.h index b8f17e5d79d7968b032d9a49715bf815130edeaa..e2c333332aa880c4593748a948570df71709da95 100644 --- a/src/AutoPilotPlugins/AutoPilotPluginManager.h +++ b/src/AutoPilotPlugins/AutoPilotPluginManager.h @@ -49,7 +49,6 @@ public: private: /// All access to singleton is through AutoPilotPluginManager::instance AutoPilotPluginManager(QObject* parent = NULL); - ~AutoPilotPluginManager(); }; #endif diff --git a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc index 21ddf364e2b799b294b06bea79afed7500df774f..d334a10158446205faa01f817c6bc9fed28ce03e 100644 --- a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc @@ -31,14 +31,6 @@ GenericAutoPilotPlugin::GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent AutoPilotPlugin(vehicle, parent) { Q_ASSERT(vehicle); - - // This kicks off parameter load - _firmwarePlugin->getParameterLoader(this, vehicle); -} - -void GenericAutoPilotPlugin::clearStaticData(void) -{ - // No Static data yet } const QVariantList& GenericAutoPilotPlugin::vehicleComponents(void) diff --git a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h index 161280c849ec25c2f3b06dbf36db0ce104bb18a1..2a09c02450af9077ce54ca3ff55d9e1207fa4023 100644 --- a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h +++ b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h @@ -40,8 +40,6 @@ public: // Overrides from AutoPilotPlugin virtual const QVariantList& vehicleComponents(void); - - static void clearStaticData(void); public slots: // FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle diff --git a/src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc b/src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc index 3b5b1fd5ae05e9348e6bc90128798d32733b9505..eff7241938640637f05c326ec533efdc965d94cd 100644 --- a/src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc +++ b/src/AutoPilotPlugins/PX4/PX4AirframeLoader.cc @@ -190,9 +190,3 @@ void PX4AirframeLoader::loadAirframeFactMetaData(void) _airframeMetaDataLoaded = true; } - -void PX4AirframeLoader::clearStaticData(void) -{ - AirframeComponentAirframes::clear(); - _airframeMetaDataLoaded = false; -} diff --git a/src/AutoPilotPlugins/PX4/PX4AirframeLoader.h b/src/AutoPilotPlugins/PX4/PX4AirframeLoader.h index 84d6e778d29ac10c8e95bf20ed7270a6a650a17a..2843ccf30353f230b5f114704f1f5615bc451f29 100644 --- a/src/AutoPilotPlugins/PX4/PX4AirframeLoader.h +++ b/src/AutoPilotPlugins/PX4/PX4AirframeLoader.h @@ -50,7 +50,6 @@ public: PX4AirframeLoader(AutoPilotPlugin* autpilot,UASInterface* uas, QObject* parent = NULL); static void loadAirframeFactMetaData(void); - static void clearStaticData(void); private: enum { diff --git a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc index c4bc00e73f8a323a1bbcb8ccedf3ef1e7de63de3..c4ef8a386441dc11229cafec589180ec55647b64 100644 --- a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc @@ -28,7 +28,7 @@ #include "AirframeComponentController.h" #include "QGCMessageBox.h" #include "UAS.h" -#include "FirmwarePlugin/PX4/PX4ParameterLoader.h" // FIXME: Hack +#include "FirmwarePlugin/PX4/PX4ParameterMetaData.h" // FIXME: Hack #include "FirmwarePlugin/PX4/PX4FirmwarePlugin.h" // FIXME: Hack /// @file @@ -81,9 +81,6 @@ PX4AutoPilotPlugin::PX4AutoPilotPlugin(Vehicle* vehicle, QObject* parent) : Q_CHECK_PTR(_airframeFacts); PX4AirframeLoader::loadAirframeFactMetaData(); - - // This kicks off parameter load - _firmwarePlugin->getParameterLoader(this, vehicle); } PX4AutoPilotPlugin::~PX4AutoPilotPlugin() @@ -91,12 +88,6 @@ PX4AutoPilotPlugin::~PX4AutoPilotPlugin() delete _airframeFacts; } -void PX4AutoPilotPlugin::clearStaticData(void) -{ - PX4ParameterLoader::clearStaticData(); - PX4AirframeLoader::clearStaticData(); -} - const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void) { if (_components.count() == 0 && !_incorrectParameterVersion) { diff --git a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h index 09b2ea8fed1e688a045a65cbf02e64b5be96f1b3..e23ac9fcdd6e14eb12e4091f1720b7d9a33e3cbf 100644 --- a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h +++ b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h @@ -51,8 +51,6 @@ public: // Overrides from AutoPilotPlugin virtual const QVariantList& vehicleComponents(void); - static void clearStaticData(void); - // These methods should only be used by objects within the plugin AirframeComponent* airframeComponent(void) { return _airframeComponent; } RadioComponent* radioComponent(void) { return _radioComponent; } diff --git a/src/FactSystem/FactSystem.h b/src/FactSystem/FactSystem.h index 91daf249e951590964b38241baad1c7e6d0bbda1..9708010cad253d242acf5bbd0597f59b010ce240 100644 --- a/src/FactSystem/FactSystem.h +++ b/src/FactSystem/FactSystem.h @@ -37,7 +37,7 @@ /// 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 /// settings. Client code can then use this system to expose sets of Facts to QML code. An example -/// of this is the PX4ParameterLoader onbject which is part of the PX4 AutoPilot plugin. It exposes +/// 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 diff --git a/src/FactSystem/ParameterLoader.cc b/src/FactSystem/ParameterLoader.cc index f46e38488013d391e0d93f983374ca8d4c6a8933..0f77589b55dacf2f20a25b24809e232caf717c3b 100644 --- a/src/FactSystem/ParameterLoader.cc +++ b/src/FactSystem/ParameterLoader.cc @@ -198,7 +198,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param // Attempt to determine default component id if (_defaultComponentId == FactSystem::defaultComponentId && _defaultComponentIdParam.isEmpty()) { - _defaultComponentIdParam = getDefaultComponentIdParam(); + _defaultComponentIdParam = _vehicle->firmwarePlugin()->getDefaultComponentIdParam(); } if (!_defaultComponentIdParam.isEmpty() && _defaultComponentIdParam == parameterName) { _defaultComponentId = componentId; @@ -255,7 +255,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param fact->_containerSetValue(value); if (setMetaData) { - _addMetaDataToFact(fact); + _vehicle->firmwarePlugin()->addMetaDataToFact(fact); } _dataMutex.unlock(); @@ -293,12 +293,6 @@ void ParameterLoader::_valueUpdated(const QVariant& value) qCDebug(ParameterLoaderLog) << "Set parameter (componentId:" << componentId << "name:" << name << value << ")"; } -void ParameterLoader::_addMetaDataToFact(Fact* fact) -{ - FactMetaData* metaData = new FactMetaData(fact->type(), this); - fact->setMetaData(metaData); -} - void ParameterLoader::refreshAllParameters(void) { _dataMutex.lock(); diff --git a/src/FactSystem/ParameterLoader.h b/src/FactSystem/ParameterLoader.h index 14f4a6cd7432fae2fb6637d077a100d4878a6e47..483111daace3b7df3c06971542be245281ce3e81 100644 --- a/src/FactSystem/ParameterLoader.h +++ b/src/FactSystem/ParameterLoader.h @@ -86,10 +86,6 @@ public: QString readParametersFromStream(QTextStream& stream); void writeParametersToStream(QTextStream &stream, const QString& name); - - /// Return the parameter for which the default component id is derived from. Return an empty - /// string is this is not available. - virtual QString getDefaultComponentIdParam(void) const = 0; signals: /// Signalled when the full set of facts are ready @@ -102,10 +98,6 @@ signals: void restartWaitingParamTimer(void); protected: - /// Base implementation adds generic meta data based on variant type. Derived class can override to provide - /// more details meta data. - virtual void _addMetaDataToFact(Fact* fact); - AutoPilotPlugin* _autopilot; Vehicle* _vehicle; MAVLinkProtocol* _mavlink; diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 4b4f7f4ed5b1c72aacb5bc1218d95fbb07e92c21..46a44aeeca762508dc3fafd8d8580fe06576e3e0 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -141,7 +141,6 @@ QString APMCustomMode::modeString() const APMFirmwarePlugin::APMFirmwarePlugin(QObject* parent) : FirmwarePlugin(parent) - , _parameterLoader(NULL) { _textSeverityAdjustmentNeeded = false; } @@ -387,18 +386,7 @@ bool APMFirmwarePlugin::sendHomePositionToVehicle(void) return true; } -ParameterLoader* APMFirmwarePlugin::getParameterLoader(AutoPilotPlugin* autopilotPlugin, Vehicle* vehicle) +void APMFirmwarePlugin::addMetaDataToFact(Fact* fact) { - if (!_parameterLoader) { - _parameterLoader = new APMParameterLoader(autopilotPlugin, vehicle, this); - Q_CHECK_PTR(_parameterLoader); - - // FIXME: Why do I need SIGNAL/SLOT to make this work - connect(_parameterLoader, SIGNAL(parametersReady(bool)), autopilotPlugin, SLOT(_parametersReadyPreChecks(bool))); - connect(_parameterLoader, &APMParameterLoader::parameterListProgress, autopilotPlugin, &APMAutoPilotPlugin::parameterListProgress); - - _parameterLoader->loadParameterFactMetaData(); - } - - return _parameterLoader; + _parameterMetaData.addMetaDataToFact(fact); } diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h index 2a7370b852ab1b0b2d16b1cffc9792fa24c5f44e..bc5fe1f664371705c0bcfc4e00f6f082610a173e 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h @@ -29,7 +29,7 @@ #include "FirmwarePlugin.h" #include "QGCLoggingCategory.h" -#include "APMParameterLoader.h" +#include "APMParameterMetaData.h" Q_DECLARE_LOGGING_CATEGORY(APMFirmwarePluginLog) @@ -89,7 +89,8 @@ public: virtual void adjustMavlinkMessage(mavlink_message_t* message); virtual void initializeVehicle(Vehicle* vehicle); virtual bool sendHomePositionToVehicle(void); - virtual ParameterLoader* getParameterLoader(AutoPilotPlugin *autopilotPlugin, Vehicle* vehicle); + virtual void addMetaDataToFact(Fact* fact); + virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); } protected: /// All access to singleton is through stack specific implementation @@ -103,7 +104,7 @@ private: APMFirmwareVersion _firmwareVersion; bool _textSeverityAdjustmentNeeded; QList _supportedModes; - APMParameterLoader* _parameterLoader; + APMParameterMetaData _parameterMetaData; }; #endif diff --git a/src/FirmwarePlugin/APM/APMParameterLoader.cc b/src/FirmwarePlugin/APM/APMParameterMetaData.cc similarity index 73% rename from src/FirmwarePlugin/APM/APMParameterLoader.cc rename to src/FirmwarePlugin/APM/APMParameterMetaData.cc index c24acf32fb4091d4c068788084ec0226b086cf33..1b929d739bda7a96ccf134ff48485ffb71f4b709 100644 --- a/src/FirmwarePlugin/APM/APMParameterLoader.cc +++ b/src/FirmwarePlugin/APM/APMParameterMetaData.cc @@ -24,7 +24,7 @@ /// @file /// @author Don Gagne -#include "APMParameterLoader.h" +#include "APMParameterMetaData.h" #include "QGCApplication.h" #include "QGCLoggingCategory.h" @@ -33,15 +33,15 @@ #include #include -QGC_LOGGING_CATEGORY(APMParameterLoaderLog, "APMParameterLoaderLog") +QGC_LOGGING_CATEGORY(APMParameterMetaDataLog, "APMParameterMetaDataLog") -bool APMParameterLoader::_parameterMetaDataLoaded = false; -QMap APMParameterLoader::_mapParameterName2FactMetaData; +bool APMParameterMetaData::_parameterMetaDataLoaded = false; +QMap APMParameterMetaData::_mapParameterName2FactMetaData; -APMParameterLoader::APMParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) : - ParameterLoader(autopilot, vehicle, parent) +APMParameterMetaData::APMParameterMetaData(QObject* parent) : + QObject(parent) { - Q_ASSERT(vehicle); + _loadParameterFactMetaData(); } /// Converts a string to a typed QVariant @@ -49,7 +49,7 @@ APMParameterLoader::APMParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehi /// @param type Type for Fact which dictates the QVariant type as well /// @param convertOk Returned: true: conversion success, false: conversion failure /// @return Returns the correctly type QVariant -QVariant APMParameterLoader::_stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk) +QVariant APMParameterMetaData::_stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk) { QVariant var(string); @@ -81,7 +81,7 @@ QVariant APMParameterLoader::_stringToTypedVariant(const QString& string, FactMe /// Load Parameter Fact meta data /// /// The meta data comes from firmware parameters.xml file. -void APMParameterLoader::loadParameterFactMetaData(void) +void APMParameterMetaData::_loadParameterFactMetaData(void) { if (_parameterMetaDataLoaded) { return; @@ -94,20 +94,11 @@ void APMParameterLoader::loadParameterFactMetaData(void) // has multiple sets of static meta data } -void APMParameterLoader::clearStaticData(void) -{ - foreach(QString parameterName, _mapParameterName2FactMetaData.keys()) { - delete _mapParameterName2FactMetaData[parameterName]; - } - _mapParameterName2FactMetaData.clear(); - _parameterMetaDataLoaded = false; -} - /// Override from FactLoad which connects the meta data to the fact -void APMParameterLoader::_addMetaDataToFact(Fact* fact) +void APMParameterMetaData::addMetaDataToFact(Fact* fact) { // FIXME: Will need to switch here based on _vehicle->firmwareType() to pull right set of meta data - // Use generic meta data - ParameterLoader::_addMetaDataToFact(fact); + FactMetaData* metaData = new FactMetaData(fact->type(), fact); + fact->setMetaData(metaData); } diff --git a/src/FirmwarePlugin/APM/APMParameterLoader.h b/src/FirmwarePlugin/APM/APMParameterMetaData.h similarity index 80% rename from src/FirmwarePlugin/APM/APMParameterLoader.h rename to src/FirmwarePlugin/APM/APMParameterMetaData.h index 4853b8aadf13a41111eae43f72de1d3a7308d901..0290dfcd3338466b3da73a49c07abc0013bd5dd2 100644 --- a/src/FirmwarePlugin/APM/APMParameterLoader.h +++ b/src/FirmwarePlugin/APM/APMParameterMetaData.h @@ -21,15 +21,14 @@ ======================================================================*/ -#ifndef APMParameterLoader_H -#define APMParameterLoader_H +#ifndef APMParameterMetaData_H +#define APMParameterMetaData_H #include #include #include #include -#include "ParameterLoader.h" #include "FactSystem.h" #include "AutoPilotPlugin.h" #include "Vehicle.h" @@ -37,24 +36,24 @@ /// @file /// @author Don Gagne -Q_DECLARE_LOGGING_CATEGORY(APMParameterLoaderLog) +Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataLog) /// Collection of Parameter Facts for PX4 AutoPilot -class APMParameterLoader : public ParameterLoader +class APMParameterMetaData : public QObject { Q_OBJECT public: /// @param uas Uas which this set of facts is associated with - APMParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL); + APMParameterMetaData(QObject* parent = NULL); /// Override from ParameterLoader - virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); } - - static void loadParameterFactMetaData(void); - static void clearStaticData(void); + virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); } + // Overrides from ParameterLoader + static void addMetaDataToFact(Fact* fact); + private: enum { XmlStateNone, @@ -65,10 +64,8 @@ private: XmlStateDone }; - // Overrides from ParameterLoader - virtual void _addMetaDataToFact(Fact* fact); - // Class methods + static void _loadParameterFactMetaData(void); static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk); static bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index a6a0b0a7f38baa0bf90356358423528a85136dcd..6e389c835fbd7ee7065313e5ac42baac9f22767b 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -105,8 +105,11 @@ public: /// false: Do not send first item to vehicle, sequence numbers must be adjusted virtual bool sendHomePositionToVehicle(void) = 0; - /// Returns the ParameterLoader - virtual ParameterLoader* getParameterLoader(AutoPilotPlugin* autopilotPlugin, Vehicle* vehicle) = 0; + /// Returns the parameter that is used to identify the default component + virtual QString getDefaultComponentIdParam(void) const = 0; + + /// Adds the parameter meta data to the Fact + virtual void addMetaDataToFact(Fact* fact) = 0; protected: FirmwarePlugin(QObject* parent = NULL) : QGCSingleton(parent) { } diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc index a7036270f15ba4f21a74fdc87bec730bfe66b4b9..9d62a42d1f714b2867d6c3b541ba5030d113a93e 100644 --- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc +++ b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc @@ -33,7 +33,6 @@ IMPLEMENT_QGC_SINGLETON(GenericFirmwarePlugin, FirmwarePlugin) GenericFirmwarePlugin::GenericFirmwarePlugin(QObject* parent) : FirmwarePlugin(parent) - , _parameterLoader(NULL) { } @@ -121,16 +120,9 @@ bool GenericFirmwarePlugin::sendHomePositionToVehicle(void) return false; } -ParameterLoader* GenericFirmwarePlugin::getParameterLoader(AutoPilotPlugin* autopilotPlugin, Vehicle* vehicle) +void GenericFirmwarePlugin::addMetaDataToFact(Fact* fact) { - if (!_parameterLoader) { - _parameterLoader = new GenericParameterLoader(autopilotPlugin, vehicle, this); - Q_CHECK_PTR(_parameterLoader); - - // FIXME: Why do I need SIGNAL/SLOT to make this work - connect(_parameterLoader, SIGNAL(parametersReady(bool)), autopilotPlugin, SLOT(_parametersReadyPreChecks(bool))); - connect(_parameterLoader, &GenericParameterLoader::parameterListProgress, autopilotPlugin, &GenericAutoPilotPlugin::parameterListProgress); - } - - return _parameterLoader; + // Add default meta data + FactMetaData* metaData = new FactMetaData(fact->type(), fact); + fact->setMetaData(metaData); } diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h index afc8c8df2c6f20e85ea28b5164f810fda636ea19..d488332eb968fa28a1a93fc97717dcff37308273 100644 --- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h +++ b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h @@ -28,7 +28,6 @@ #define GenericFirmwarePlugin_H #include "FirmwarePlugin.h" -#include "GenericParameterLoader.h" class GenericFirmwarePlugin : public FirmwarePlugin { @@ -48,13 +47,12 @@ public: virtual void adjustMavlinkMessage(mavlink_message_t* message); virtual void initializeVehicle(Vehicle* vehicle); virtual bool sendHomePositionToVehicle(void); - virtual ParameterLoader* getParameterLoader(AutoPilotPlugin *autopilotPlugin, Vehicle* vehicle); + virtual void addMetaDataToFact(Fact* fact); + virtual QString getDefaultComponentIdParam(void) const { return QString(); } private: /// All access to singleton is through AutoPilotPluginManager::instance GenericFirmwarePlugin(QObject* parent = NULL); - - GenericParameterLoader* _parameterLoader; }; #endif diff --git a/src/FirmwarePlugin/Generic/GenericParameterLoader.cc b/src/FirmwarePlugin/Generic/GenericParameterLoader.cc deleted file mode 100644 index 20439ea226c78c35e367b81e4884cbcd493bafa6..0000000000000000000000000000000000000000 --- a/src/FirmwarePlugin/Generic/GenericParameterLoader.cc +++ /dev/null @@ -1,37 +0,0 @@ -/*===================================================================== - - QGroundControl Open Source Ground Control Station - - (c) 2009 - 2014 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 "GenericParameterLoader.h" - -GenericParameterLoader::GenericParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) : - ParameterLoader(autopilot, vehicle, parent) -{ - Q_ASSERT(vehicle); -} - -/// Override from ParameterLoader which connects the meta data to the fact -void GenericParameterLoader::_addMetaDataToFact(Fact* fact) -{ - // Use generic meta data - ParameterLoader::_addMetaDataToFact(fact); -} diff --git a/src/FirmwarePlugin/Generic/GenericParameterLoader.h b/src/FirmwarePlugin/Generic/GenericParameterLoader.h deleted file mode 100644 index 98aa7f2cda6bf9ba9db31f7258f898a0e26939ba..0000000000000000000000000000000000000000 --- a/src/FirmwarePlugin/Generic/GenericParameterLoader.h +++ /dev/null @@ -1,48 +0,0 @@ -/*===================================================================== - - QGroundControl Open Source Ground Control Station - - (c) 2009 - 2014 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 GenericParameterLoader_H -#define GenericParameterLoader_H - -#include "ParameterLoader.h" -#include "FactSystem.h" -#include "AutoPilotPlugin.h" -#include "Vehicle.h" - -class GenericParameterLoader : public ParameterLoader -{ - Q_OBJECT - -public: - /// @param uas Uas which this set of facts is associated with - GenericParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL); - - /// Override from ParameterLoader - virtual QString getDefaultComponentIdParam(void) const { return QString(); } - -private: - // Overrides from ParameterLoader - virtual void _addMetaDataToFact(Fact* fact); -}; - -#endif diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index b86c89d475980f775bf8704a3965a3008f4d33e5..77da20de535df55e9a002db5a1944396beffdb2f 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -90,7 +90,6 @@ static const struct Modes2Name rgModes2Name[] = { PX4FirmwarePlugin::PX4FirmwarePlugin(QObject* parent) : FirmwarePlugin(parent) - , _parameterLoader(NULL) { } @@ -212,18 +211,7 @@ bool PX4FirmwarePlugin::sendHomePositionToVehicle(void) return false; } -ParameterLoader* PX4FirmwarePlugin::getParameterLoader(AutoPilotPlugin* autopilotPlugin, Vehicle* vehicle) +void PX4FirmwarePlugin::addMetaDataToFact(Fact* fact) { - if (!_parameterLoader) { - _parameterLoader = new PX4ParameterLoader(autopilotPlugin, vehicle, this); - Q_CHECK_PTR(_parameterLoader); - - // FIXME: Why do I need SIGNAL/SLOT to make this work - connect(_parameterLoader, SIGNAL(parametersReady(bool)), autopilotPlugin, SLOT(_parametersReadyPreChecks(bool))); - connect(_parameterLoader, &PX4ParameterLoader::parameterListProgress, autopilotPlugin, &PX4AutoPilotPlugin::parameterListProgress); - - _parameterLoader->loadParameterFactMetaData(); - } - - return _parameterLoader; + _parameterMetaData.addMetaDataToFact(fact); } diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h index a78693a3a871797b30331b3b1eb5451772fe09f4..73063286f9f89cb90e2451c5b3166281f771edc6 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h @@ -28,7 +28,7 @@ #define PX4FirmwarePlugin_H #include "FirmwarePlugin.h" -#include "PX4ParameterLoader.h" +#include "PX4ParameterMetaData.h" class PX4FirmwarePlugin : public FirmwarePlugin { @@ -48,13 +48,14 @@ public: virtual void adjustMavlinkMessage(mavlink_message_t* message); virtual void initializeVehicle(Vehicle* vehicle); virtual bool sendHomePositionToVehicle(void); - virtual ParameterLoader* getParameterLoader(AutoPilotPlugin *autopilotPlugin, Vehicle* vehicle); + virtual void addMetaDataToFact(Fact* fact); + virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); } private: /// All access to singleton is through AutoPilotPluginManager::instance PX4FirmwarePlugin(QObject* parent = NULL); - PX4ParameterLoader* _parameterLoader; + PX4ParameterMetaData _parameterMetaData; }; #endif diff --git a/src/FirmwarePlugin/PX4/PX4ParameterLoader.cc b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc similarity index 81% rename from src/FirmwarePlugin/PX4/PX4ParameterLoader.cc rename to src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc index c7d989dd263e2fa1ac238860336992dd9c3caeb8..9e370fc3891dcda3333e2c7b1f739f991fc3ce3e 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterLoader.cc +++ b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc @@ -24,7 +24,7 @@ /// @file /// @author Don Gagne -#include "PX4ParameterLoader.h" +#include "PX4ParameterMetaData.h" #include "QGCApplication.h" #include "QGCLoggingCategory.h" @@ -33,15 +33,15 @@ #include #include -QGC_LOGGING_CATEGORY(PX4ParameterLoaderLog, "PX4ParameterLoaderLog") +QGC_LOGGING_CATEGORY(PX4ParameterMetaDataLog, "PX4ParameterMetaDataLog") -bool PX4ParameterLoader::_parameterMetaDataLoaded = false; -QMap PX4ParameterLoader::_mapParameterName2FactMetaData; +bool PX4ParameterMetaData::_parameterMetaDataLoaded = false; +QMap PX4ParameterMetaData::_mapParameterName2FactMetaData; -PX4ParameterLoader::PX4ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) : - ParameterLoader(autopilot, vehicle, parent) +PX4ParameterMetaData::PX4ParameterMetaData(QObject* parent) : + QObject(parent) { - Q_ASSERT(vehicle); + } /// Converts a string to a typed QVariant @@ -49,7 +49,7 @@ PX4ParameterLoader::PX4ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehi /// @param type Type for Fact which dictates the QVariant type as well /// @param convertOk Returned: true: conversion success, false: conversion failure /// @return Returns the correctly type QVariant -QVariant PX4ParameterLoader::_stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk) +QVariant PX4ParameterMetaData::_stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk) { QVariant var(string); @@ -81,14 +81,14 @@ QVariant PX4ParameterLoader::_stringToTypedVariant(const QString& string, FactMe /// Load Parameter Fact meta data /// /// The meta data comes from firmware parameters.xml file. -void PX4ParameterLoader::loadParameterFactMetaData(void) +void PX4ParameterMetaData::_loadParameterFactMetaData(void) { if (_parameterMetaDataLoaded) { return; } _parameterMetaDataLoaded = true; - qCDebug(PX4ParameterLoaderLog) << "Loading PX4 parameter fact meta data"; + qCDebug(PX4ParameterMetaDataLog) << "Loading PX4 parameter fact meta data"; Q_ASSERT(_mapParameterName2FactMetaData.count() == 0); @@ -105,7 +105,7 @@ void PX4ParameterLoader::loadParameterFactMetaData(void) parameterFilename = ":/AutoPilotPlugins/PX4/ParameterFactMetaData.xml"; } - qCDebug(PX4ParameterLoaderLog) << "Loading parameter meta data:" << parameterFilename; + qCDebug(PX4ParameterMetaDataLog) << "Loading parameter meta data:" << parameterFilename; QFile xmlFile(parameterFilename); Q_ASSERT(xmlFile.exists()); @@ -172,7 +172,7 @@ void PX4ParameterLoader::loadParameterFactMetaData(void) return; } factGroup = xml.attributes().value("name").toString(); - qCDebug(PX4ParameterLoaderLog) << "Found group: " << factGroup; + qCDebug(PX4ParameterMetaDataLog) << "Found group: " << factGroup; } else if (elementName == "parameter") { if (xmlState != XmlStateFoundGroup) { @@ -190,7 +190,7 @@ void PX4ParameterLoader::loadParameterFactMetaData(void) QString type = xml.attributes().value("type").toString(); QString strDefault = xml.attributes().value("default").toString(); - qCDebug(PX4ParameterLoaderLog) << "Found parameter name:" << name << " type:" << type << " default:" << strDefault; + qCDebug(PX4ParameterMetaDataLog) << "Found parameter name:" << name << " type:" << type << " default:" << strDefault; // Convert type from string to FactMetaData::ValueType_t @@ -227,7 +227,7 @@ void PX4ParameterLoader::loadParameterFactMetaData(void) Q_CHECK_PTR(metaData); if (_mapParameterName2FactMetaData.contains(name)) { // We can't trust the meta dafa since we have dups - qCWarning(PX4ParameterLoaderLog) << "Duplicate parameter found:" << name; + qCWarning(PX4ParameterMetaDataLog) << "Duplicate parameter found:" << name; badMetaData = true; // Reset to default meta data _mapParameterName2FactMetaData[name] = metaData; @@ -242,7 +242,7 @@ void PX4ParameterLoader::loadParameterFactMetaData(void) if (metaData->convertAndValidate(strDefault, false, varDefault, errorString)) { metaData->setDefaultValue(varDefault); } else { - qCWarning(PX4ParameterLoaderLog) << "Invalid default value, name:" << name << " type:" << type << " default:" << strDefault << " error:" << errorString; + qCWarning(PX4ParameterMetaDataLog) << "Invalid default value, name:" << name << " type:" << type << " default:" << strDefault << " error:" << errorString; } } } @@ -259,57 +259,57 @@ void PX4ParameterLoader::loadParameterFactMetaData(void) Q_ASSERT(metaData); QString text = xml.readElementText(); text = text.replace("\n", " "); - qCDebug(PX4ParameterLoaderLog) << "Short description:" << text; + qCDebug(PX4ParameterMetaDataLog) << "Short description:" << text; metaData->setShortDescription(text); } else if (elementName == "long_desc") { Q_ASSERT(metaData); QString text = xml.readElementText(); text = text.replace("\n", " "); - qCDebug(PX4ParameterLoaderLog) << "Long description:" << text; + qCDebug(PX4ParameterMetaDataLog) << "Long description:" << text; metaData->setLongDescription(text); } else if (elementName == "min") { Q_ASSERT(metaData); QString text = xml.readElementText(); - qCDebug(PX4ParameterLoaderLog) << "Min:" << text; + qCDebug(PX4ParameterMetaDataLog) << "Min:" << text; QVariant varMin; if (metaData->convertAndValidate(text, true /* convertOnly */, varMin, errorString)) { metaData->setMin(varMin); } else { - qCWarning(PX4ParameterLoaderLog) << "Invalid min value, name:" << metaData->name() << " type:" << metaData->type() << " min:" << text << " error:" << errorString; + qCWarning(PX4ParameterMetaDataLog) << "Invalid min value, name:" << metaData->name() << " type:" << metaData->type() << " min:" << text << " error:" << errorString; } } else if (elementName == "max") { Q_ASSERT(metaData); QString text = xml.readElementText(); - qCDebug(PX4ParameterLoaderLog) << "Max:" << text; + qCDebug(PX4ParameterMetaDataLog) << "Max:" << text; QVariant varMax; if (metaData->convertAndValidate(text, true /* convertOnly */, varMax, errorString)) { metaData->setMax(varMax); } else { - qCWarning(PX4ParameterLoaderLog) << "Invalid max value, name:" << metaData->name() << " type:" << metaData->type() << " max:" << text << " error:" << errorString; + qCWarning(PX4ParameterMetaDataLog) << "Invalid max value, name:" << metaData->name() << " type:" << metaData->type() << " max:" << text << " error:" << errorString; } } else if (elementName == "unit") { Q_ASSERT(metaData); QString text = xml.readElementText(); - qCDebug(PX4ParameterLoaderLog) << "Unit:" << text; + qCDebug(PX4ParameterMetaDataLog) << "Unit:" << text; metaData->setUnits(text); } else if (elementName == "decimal") { Q_ASSERT(metaData); QString text = xml.readElementText(); - qCDebug(PX4ParameterLoaderLog) << "Decimal:" << text; + qCDebug(PX4ParameterMetaDataLog) << "Decimal:" << text; bool convertOk; QVariant varDecimals = QVariant(text).toUInt(&convertOk); if (convertOk) { metaData->setDecimalPlaces(varDecimals.toInt()); } else { - qCWarning(PX4ParameterLoaderLog) << "Invalid decimals value, name:" << metaData->name() << " type:" << metaData->type() << " decimals:" << text << " error: invalid number"; + qCWarning(PX4ParameterMetaDataLog) << "Invalid decimals value, name:" << metaData->name() << " type:" << metaData->type() << " decimals:" << text << " error: invalid number"; } } else { @@ -326,7 +326,7 @@ void PX4ParameterLoader::loadParameterFactMetaData(void) QVariant var; if (!metaData->convertAndValidate(metaData->defaultValue(), false /* convertOnly */, var, errorString)) { - qCWarning(PX4ParameterLoaderLog) << "Invalid default value, name:" << metaData->name() << " type:" << metaData->type() << " default:" << metaData->defaultValue() << " error:" << errorString; + qCWarning(PX4ParameterMetaDataLog) << "Invalid default value, name:" << metaData->name() << " type:" << metaData->type() << " default:" << metaData->defaultValue() << " error:" << errorString; } } @@ -344,22 +344,14 @@ void PX4ParameterLoader::loadParameterFactMetaData(void) } } -void PX4ParameterLoader::clearStaticData(void) -{ - foreach(QString parameterName, _mapParameterName2FactMetaData.keys()) { - delete _mapParameterName2FactMetaData[parameterName]; - } - _mapParameterName2FactMetaData.clear(); - _parameterMetaDataLoaded = false; -} - /// Override from FactLoad which connects the meta data to the fact -void PX4ParameterLoader::_addMetaDataToFact(Fact* fact) +void PX4ParameterMetaData::addMetaDataToFact(Fact* fact) { if (_mapParameterName2FactMetaData.contains(fact->name())) { fact->setMetaData(_mapParameterName2FactMetaData[fact->name()]); } else { // Use generic meta data - ParameterLoader::_addMetaDataToFact(fact); + FactMetaData* metaData = new FactMetaData(fact->type(), fact); + fact->setMetaData(metaData); } } diff --git a/src/FirmwarePlugin/PX4/PX4ParameterLoader.h b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h similarity index 71% rename from src/FirmwarePlugin/PX4/PX4ParameterLoader.h rename to src/FirmwarePlugin/PX4/PX4ParameterMetaData.h index 8d4b8b91d30f01a33e149fc39f2cdef903f2d84c..c2d1822ef7d1d0f872f1b3748dd56368dc8001b7 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterLoader.h +++ b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h @@ -21,15 +21,14 @@ ======================================================================*/ -#ifndef PX4PARAMETERLOADER_H -#define PX4PARAMETERLOADER_H +#ifndef PX4ParameterMetaData_H +#define PX4ParameterMetaData_H #include #include #include #include -#include "ParameterLoader.h" #include "FactSystem.h" #include "AutoPilotPlugin.h" #include "Vehicle.h" @@ -37,24 +36,19 @@ /// @file /// @author Don Gagne -Q_DECLARE_LOGGING_CATEGORY(PX4ParameterLoaderLog) +Q_DECLARE_LOGGING_CATEGORY(PX4ParameterMetaDataLog) /// Collection of Parameter Facts for PX4 AutoPilot -class PX4ParameterLoader : public ParameterLoader +class PX4ParameterMetaData : public QObject { Q_OBJECT public: - /// @param uas Uas which this set of facts is associated with - PX4ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent = NULL); + PX4ParameterMetaData(QObject* parent = NULL); + + void addMetaDataToFact(Fact* fact); - /// Override from ParameterLoader - virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); } - - static void loadParameterFactMetaData(void); - static void clearStaticData(void); - private: enum { XmlStateNone, @@ -63,16 +57,13 @@ private: XmlStateFoundGroup, XmlStateFoundParameter, XmlStateDone - }; - - // Overrides from ParameterLoader - virtual void _addMetaDataToFact(Fact* fact); + }; - // Class methods + static void _loadParameterFactMetaData(void); static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk); static bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded static QMap _mapParameterName2FactMetaData; ///< Maps from a parameter name to FactMetaData }; -#endif \ No newline at end of file +#endif diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index ebb3b6a66912dbbaf7fdf96ceaa4606abcc0497c..cf2bdfbebfc5ae2e3b15ae3a806268c08854f021 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -32,6 +32,7 @@ #include "JoystickManager.h" #include "MissionManager.h" #include "CoordinateVector.h" +#include "ParameterLoader.h" QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog") @@ -89,6 +90,7 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType, , _updateCount(0) , _missionManager(NULL) , _missionManagerInitialRequestComplete(false) + , _parameterLoader(NULL) , _armed(false) , _base_mode(0) , _custom_mode(0) @@ -154,9 +156,13 @@ Vehicle::Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType, _loadSettings(); - _missionManager = new MissionManager(this); - connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError); - + _missionManager = new MissionManager(this); + connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError); + + _parameterLoader = new ParameterLoader(_autopilotPlugin, this /* Vehicle */, this /* parent */); + connect(_parameterLoader, SIGNAL(parametersReady(bool)), _autopilotPlugin, SLOT(_parametersReadyPreChecks(bool))); + connect(_parameterLoader, SIGNAL(parameterListProgress(float)), _autopilotPlugin, SLOT(parameterListProgress(float))); + _firmwarePlugin->initializeVehicle(this); _sendMultipleTimer.start(_sendMessageMultipleIntraMessageDelay); @@ -1148,3 +1154,8 @@ void Vehicle::_communicationInactivityTimedOut(void) linkMgr->disconnectLink(_links[i].data()); } } + +ParameterLoader* Vehicle::getParameterLoader(void) +{ + return _parameterLoader; +} diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 6fbf286ae36c5a44d4690e2042d0ade48d27db1d..eb0666f855993eda19c91a11caf11cb8c339e922 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -42,6 +42,7 @@ class UASInterface; class FirmwarePlugin; class AutoPilotPlugin; class MissionManager; +class ParameterLoader; Q_DECLARE_LOGGING_CATEGORY(VehicleLog) @@ -248,6 +249,8 @@ public: double waypointDistance () { return _waypointDistance; } uint16_t currentWaypoint () { return _currentWaypoint; } unsigned int heartbeatTimeout () { return _currentHeartbeatTimeout; } + + ParameterLoader* getParameterLoader(void); public slots: void setLatitude(double latitude); @@ -411,6 +414,8 @@ private: MissionManager* _missionManager; bool _missionManagerInitialRequestComplete; + + ParameterLoader* _parameterLoader; bool _armed; ///< true: vehicle is armed uint8_t _base_mode; ///< base_mode from HEARTBEAT