From e950558856ddac246a4e77a6aa6d913527eb99c3 Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Fri, 12 Jan 2018 12:23:05 -0800 Subject: [PATCH] Add support for volatile Facts/Parameters --- src/FactSystem/Fact.cc | 10 ++ src/FactSystem/Fact.h | 2 + src/FactSystem/FactMetaData.cc | 12 ++ src/FactSystem/FactMetaData.h | 3 + src/FactSystem/ParameterManager.cc | 169 +++++++++++------- src/FactSystem/ParameterManager.h | 5 +- src/FirmwarePlugin/FirmwarePlugin.h | 5 + src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc | 20 ++- src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h | 3 +- .../PX4/PX4ParameterMetaData.cc | 27 +++ src/FirmwarePlugin/PX4/PX4ParameterMetaData.h | 5 +- 11 files changed, 189 insertions(+), 72 deletions(-) diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc index f36452b84..8930790b2 100644 --- a/src/FactSystem/Fact.cc +++ b/src/FactSystem/Fact.cc @@ -662,3 +662,13 @@ bool Fact::readOnly(void) const return false; } } + +bool Fact::volatileValue(void) const +{ + if (_metaData) { + return _metaData->volatileValue(); + } else { + qWarning() << kMissingMetadata << name(); + return false; + } +} diff --git a/src/FactSystem/Fact.h b/src/FactSystem/Fact.h index 34ba32ced..54ccd2214 100644 --- a/src/FactSystem/Fact.h +++ b/src/FactSystem/Fact.h @@ -71,6 +71,7 @@ public: Q_PROPERTY(bool typeIsBool READ typeIsBool CONSTANT) Q_PROPERTY(bool hasControl READ hasControl CONSTANT) Q_PROPERTY(bool readOnly READ readOnly CONSTANT) + Q_PROPERTY(bool volatileValue READ volatileValue CONSTANT) /// Convert and validate value /// @param convertOnly true: validate type conversion only, false: validate against meta data as well @@ -118,6 +119,7 @@ public: bool typeIsBool (void) const { return type() == FactMetaData::valueTypeBool; } bool hasControl (void) const; bool readOnly (void) const; + bool volatileValue (void) const; /// Returns the values as a string with full 18 digit precision if float/double. QString rawValueStringFullPrecision(void) const; diff --git a/src/FactSystem/FactMetaData.cc b/src/FactSystem/FactMetaData.cc index 705b32a38..e9e6e79b1 100644 --- a/src/FactSystem/FactMetaData.cc +++ b/src/FactSystem/FactMetaData.cc @@ -96,6 +96,7 @@ FactMetaData::FactMetaData(QObject* parent) , _increment (std::numeric_limits::quiet_NaN()) , _hasControl (true) , _readOnly (false) + , _volatile (false) { } @@ -118,6 +119,7 @@ FactMetaData::FactMetaData(ValueType_t type, QObject* parent) , _increment (std::numeric_limits::quiet_NaN()) , _hasControl (true) , _readOnly (false) + , _volatile (false) { } @@ -147,6 +149,7 @@ FactMetaData::FactMetaData(ValueType_t type, const QString name, QObject* parent , _increment (std::numeric_limits::quiet_NaN()) , _hasControl (true) , _readOnly (false) + , _volatile (false) { } @@ -178,6 +181,7 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other) _increment = other._increment; _hasControl = other._hasControl; _readOnly = other._readOnly; + _volatile = other._volatile; return *this; } @@ -1128,3 +1132,11 @@ QVariant FactMetaData::cookedMin(void) const return cookedMin; } } + +void FactMetaData::setVolatileValue(bool bValue) +{ + _volatile = bValue; + if (_volatile) { + _readOnly = true; + } +} diff --git a/src/FactSystem/FactMetaData.h b/src/FactSystem/FactMetaData.h index a357c726b..f9babc234 100644 --- a/src/FactSystem/FactMetaData.h +++ b/src/FactSystem/FactMetaData.h @@ -101,6 +101,7 @@ public: bool rebootRequired (void) const { return _rebootRequired; } bool hasControl (void) const { return _hasControl; } bool readOnly (void) const { return _readOnly; } + bool volatileValue (void) const { return _volatile; } /// Amount to increment value when used in controls such as spin button or slider with detents. /// NaN for no increment available. @@ -131,6 +132,7 @@ public: void setIncrement (double increment) { _increment = increment; } void setHasControl (bool bValue) { _hasControl = bValue; } void setReadOnly (bool bValue) { _readOnly = bValue; } + void setVolatileValue (bool bValue); void setTranslators(Translator rawTranslator, Translator cookedTranslator); @@ -239,6 +241,7 @@ private: double _increment; bool _hasControl; bool _readOnly; + bool _volatile; // Exact conversion constants static const struct UnitConsts_s { diff --git a/src/FactSystem/ParameterManager.cc b/src/FactSystem/ParameterManager.cc index 8858711ef..03b994d24 100644 --- a/src/FactSystem/ParameterManager.cc +++ b/src/FactSystem/ParameterManager.cc @@ -7,10 +7,6 @@ * ****************************************************************************/ - -/// @file -/// @author Don Gagne - #include "ParameterManager.h" #include "QGCApplication.h" #include "QGCLoggingCategory.h" @@ -27,9 +23,8 @@ #include /* types for local parameter cache */ -typedef QPair ParamTypeVal; -typedef QPair NamedParam; -typedef QMap MapID2NamedParam; +typedef QPair ParamTypeVal; +typedef QMap CacheMapName2ParamTypeVal; QGC_LOGGING_CATEGORY(ParameterManagerVerbose1Log, "ParameterManagerVerbose1Log") QGC_LOGGING_CATEGORY(ParameterManagerVerbose2Log, "ParameterManagerVerbose2Log") @@ -43,25 +38,26 @@ const char* ParameterManager::_jsonParamNameKey = "name"; const char* ParameterManager::_jsonParamValueKey = "value"; ParameterManager::ParameterManager(Vehicle* vehicle) - : QObject(vehicle) - , _vehicle(vehicle) - , _mavlink(NULL) - , _loadProgress(0.0) - , _parametersReady(false) - , _missingParameters(false) - , _initialLoadComplete(false) - , _waitingForDefaultComponent(false) - , _saveRequired(false) - , _logReplay(vehicle->priorityLink() && vehicle->priorityLink()->isLogReplay()) - , _parameterSetMajorVersion(-1) - , _parameterMetaData(NULL) - , _prevWaitingReadParamIndexCount(0) - , _prevWaitingReadParamNameCount(0) - , _prevWaitingWriteParamNameCount(0) - , _initialRequestRetryCount(0) - , _disableAllRetries(false) - , _indexBatchQueueActive(false) - , _totalParamCount(0) + : QObject (vehicle) + , _vehicle (vehicle) + , _mavlink (NULL) + , _loadProgress (0.0) + , _parametersReady (false) + , _missingParameters (false) + , _initialLoadComplete (false) + , _waitingForDefaultComponent (false) + , _saveRequired (false) + , _metaDataAddedToFacts (false) + , _logReplay (vehicle->priorityLink() && vehicle->priorityLink()->isLogReplay()) + , _parameterSetMajorVersion (-1) + , _parameterMetaData (NULL) + , _prevWaitingReadParamIndexCount (0) + , _prevWaitingReadParamNameCount (0) + , _prevWaitingWriteParamNameCount (0) + , _initialRequestRetryCount (0) + , _disableAllRetries (false) + , _indexBatchQueueActive (false) + , _totalParamCount (0) { _versionParam = vehicle->firmwarePlugin()->getVersionParam(); @@ -137,10 +133,12 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString } #endif - if (_vehicle->px4Firmware() && parameterName == "_HASH_CHECK" && !_logReplay) { - /* we received a cache hash, potentially load from cache */ - _tryCacheHashLoad(vehicleId, componentId, value); - return; + if (_vehicle->px4Firmware() && parameterName == "_HASH_CHECK") { + if (!_initialLoadComplete && !_logReplay) { + /* we received a cache hash, potentially load from cache */ + _tryCacheHashLoad(vehicleId, componentId, value); + } + return; } _initialRequestTimeoutTimer.stop(); @@ -154,8 +152,6 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString _totalParamCount += parameterCount; } - _mapParameterId2Name[componentId][parameterId] = parameterName; - // If we've never seen this component id before, setup the wait lists. if (!_waitingReadParamIndexMap.contains(componentId)) { // Add all indices to the wait list, parameter index is 0-based @@ -735,19 +731,18 @@ void ParameterManager::_writeParameterRaw(int componentId, const QString& paramN void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId) { - MapID2NamedParam cache_map; + CacheMapName2ParamTypeVal cacheMap; - foreach(int id, _mapParameterId2Name[componentId].keys()) { - const QString name(_mapParameterId2Name[componentId][id]); + foreach(const QString& name, _mapParameterName2Variant[componentId].keys()) { const Fact *fact = _mapParameterName2Variant[componentId][name].value(); - cache_map[id] = NamedParam(name, ParamTypeVal(fact->type(), fact->rawValue())); + cacheMap[name] = ParamTypeVal(fact->type(), fact->rawValue()); } - QFile cache_file(parameterCacheFile(vehicleId, componentId)); - cache_file.open(QIODevice::WriteOnly | QIODevice::Truncate); + QFile cacheFile(parameterCacheFile(vehicleId, componentId)); + cacheFile.open(QIODevice::WriteOnly | QIODevice::Truncate); - QDataStream ds(&cache_file); - ds << cache_map; + QDataStream ds(&cacheFile); + ds << cacheMap; } QDir ParameterManager::parameterCacheDir() @@ -758,46 +753,70 @@ QDir ParameterManager::parameterCacheDir() QString ParameterManager::parameterCacheFile(int vehicleId, int componentId) { - return parameterCacheDir().filePath(QString("%1_%2").arg(vehicleId).arg(componentId)); + return parameterCacheDir().filePath(QString("%1_%2.v2").arg(vehicleId).arg(componentId)); } void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value) { + qCInfo(ParameterManagerLog) << "Attemping load from cache"; + uint32_t crc32_value = 0; /* The datastructure of the cache table */ - MapID2NamedParam cache_map; - QFile cache_file(parameterCacheFile(vehicleId, componentId)); - if (!cache_file.exists()) { + CacheMapName2ParamTypeVal cacheMap; + QFile cacheFile(parameterCacheFile(vehicleId, componentId)); + if (!cacheFile.exists()) { /* no local cache, just wait for them to come in*/ return; } - cache_file.open(QIODevice::ReadOnly); + cacheFile.open(QIODevice::ReadOnly); /* Deserialize the parameter cache table */ - QDataStream ds(&cache_file); - ds >> cache_map; + QDataStream ds(&cacheFile); + ds >> cacheMap; + + // Load parameter meta data for the version number stored in cache. + // We need meta data so we have access to the volatile bit + if (cacheMap.contains(_versionParam)) { + _parameterSetMajorVersion = cacheMap[_versionParam].second.toInt(); + } + _loadMetaData(); /* compute the crc of the local cache to check against the remote */ - foreach(int id, cache_map.keys()) { - const QString name(cache_map[id].first); - const void *vdat = cache_map[id].second.second.constData(); - const FactMetaData::ValueType_t fact_type = static_cast(cache_map[id].second.first); - crc32_value = QGC::crc32((const uint8_t *)qPrintable(name), name.length(), crc32_value); - crc32_value = QGC::crc32((const uint8_t *)vdat, FactMetaData::typeToSize(fact_type), crc32_value); + FirmwarePlugin* firmwarePlugin = _vehicle->firmwarePlugin(); + foreach (const QString& name, cacheMap.keys()) { + bool volatileValue = false; + + FactMetaData* metaData = firmwarePlugin->getMetaDataForFact(_parameterMetaData, name, _vehicle->vehicleType()); + if (metaData) { + volatileValue = metaData->volatileValue(); + } + + if (volatileValue) { + // Does not take part in CRC + qCDebug(ParameterManagerLog) << "Volatile parameter" << name; + } else { + const ParamTypeVal& paramTypeVal = cacheMap[name]; + const void *vdat = paramTypeVal.second.constData(); + const FactMetaData::ValueType_t fact_type = static_cast(paramTypeVal.first); + crc32_value = QGC::crc32((const uint8_t *)qPrintable(name), name.length(), crc32_value); + crc32_value = QGC::crc32((const uint8_t *)vdat, FactMetaData::typeToSize(fact_type), crc32_value); + } } + /* if the two param set hashes match, just load from the disk */ if (crc32_value == hash_value.toUInt()) { - qCInfo(ParameterManagerLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cache_file).absoluteFilePath()); - /* if the two param set hashes match, just load from the disk */ - int count = cache_map.count(); - foreach(int id, cache_map.keys()) { - const QString &name = cache_map[id].first; - const QVariant &value = cache_map[id].second.second; - const FactMetaData::ValueType_t fact_type = static_cast(cache_map[id].second.first); + qCInfo(ParameterManagerLog) << "Parameters loaded from cache" << qPrintable(QFileInfo(cacheFile).absoluteFilePath()); + + int count = cacheMap.count(); + int index = 0; + foreach (const QString& name, cacheMap.keys()) { + const ParamTypeVal& paramTypeVal = cacheMap[name]; + const FactMetaData::ValueType_t fact_type = static_cast(paramTypeVal.first); const int mavType = _factTypeToMavType(fact_type); - _parameterUpdate(vehicleId, componentId, name, count, id, mavType, value); + _parameterUpdate(vehicleId, componentId, name, count, index++, mavType, paramTypeVal.second); } + // Return the hash value to notify we don't want any more updates mavlink_param_set_t p; mavlink_param_union_t union_value; @@ -836,7 +855,10 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian ani->start(QAbstractAnimation::DeleteWhenStopped); } else { - qCInfo(ParameterManagerLog) << "Parameters cache match failed" << qPrintable(QFileInfo(cache_file).absoluteFilePath()); + // Cache parameter version may differ from vehicle parameter version so we can't trust information loaded from cache parameter version number + _parameterSetMajorVersion = -1; + _clearMetaData(); + qCInfo(ParameterManagerLog) << "Parameters cache match failed" << qPrintable(QFileInfo(cacheFile).absoluteFilePath()); } } @@ -993,7 +1015,15 @@ FactMetaData::ValueType_t ParameterManager::_mavTypeToFactType(MAV_PARAM_TYPE ma } } -void ParameterManager::_addMetaDataToDefaultComponent(void) +void ParameterManager::_clearMetaData(void) +{ + if (_parameterMetaData) { + _parameterMetaData->deleteLater(); + _parameterMetaData = NULL; + } +} + +void ParameterManager::_loadMetaData(void) { if (_parameterMetaData) { return; @@ -1004,9 +1034,18 @@ void ParameterManager::_addMetaDataToDefaultComponent(void) // Load best parameter meta data set metaDataFile = parameterMetaDataFile(_vehicle, _vehicle->firmwareType(), _parameterSetMajorVersion, majorVersion, minorVersion); - qCDebug(ParameterManagerLog) << "Adding meta data to Vehicle file:major:minor" << metaDataFile << majorVersion << minorVersion; - + qCDebug(ParameterManagerLog) << "Loading meta data file:major:minor" << metaDataFile << majorVersion << minorVersion; _parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile); +} + +void ParameterManager::_addMetaDataToDefaultComponent(void) +{ + _loadMetaData(); + + if (_metaDataAddedToFacts) { + return; + } + _metaDataAddedToFacts = true; // Loop over all parameters in default component adding meta data QVariantMap& factMap = _mapParameterName2Variant[_vehicle->defaultComponentId()]; diff --git a/src/FactSystem/ParameterManager.h b/src/FactSystem/ParameterManager.h index a800acc5d..d0f45b16f 100644 --- a/src/FactSystem/ParameterManager.h +++ b/src/FactSystem/ParameterManager.h @@ -142,6 +142,8 @@ private: void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value); void _writeLocalParamCache(int vehicleId, int componentId); void _tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value); + void _loadMetaData(void); + void _clearMetaData(void); void _addMetaDataToDefaultComponent(void); QString _remapParamNameToVersion(const QString& paramName); void _loadOfflineEditingParams(void); @@ -158,8 +160,6 @@ private: /// Second mapping is parameter name, to Fact* in QVariant QMap _mapParameterName2Variant; - QMap > _mapParameterId2Name; - // Category map of default component parameters QMap > _categoryMap; @@ -169,6 +169,7 @@ private: bool _initialLoadComplete; ///< true: Initial load of all parameters complete, whether successful or not bool _waitingForDefaultComponent; ///< true: last chance wait for default component params bool _saveRequired; ///< true: _saveToEEPROM should be called + bool _metaDataAddedToFacts; ///< true: FactMetaData has been adde to the default component facts bool _logReplay; ///< true: running with log replay link QString _versionParam; ///< Parameter which contains parameter set version int _parameterSetMajorVersion; ///< Version for parameter set, -1 if not known diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index 5a8e9b5d1..4016383f1 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -218,6 +218,11 @@ public: /// call deleteParameterMetaData when no longer needed. virtual QObject* loadParameterMetaData(const QString& metaDataFile) { Q_UNUSED(metaDataFile); return NULL; } + /// Returns the FactMetaData associated with the parameter name + /// @param opaqueParameterMetaData Opaque pointer returned from loadParameterMetaData + /// @param name Parameter name + virtual FactMetaData* getMetaDataForFact(QObject* parameterMetaData, const QString& name, MAV_TYPE vehicleType) { Q_UNUSED(parameterMetaData); Q_UNUSED(name); Q_UNUSED(vehicleType); return NULL; } + /// Adds the parameter meta data to the Fact /// @param opaqueParameterMetaData Opaque pointer returned from loadParameterMetaData virtual void addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) { Q_UNUSED(parameterMetaData); Q_UNUSED(fact); Q_UNUSED(vehicleType); return; } diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index 9932a1638..1a0b3ff28 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -247,6 +247,19 @@ bool PX4FirmwarePlugin::sendHomePositionToVehicle(void) return false; } +FactMetaData* PX4FirmwarePlugin::getMetaDataForFact(QObject* parameterMetaData, const QString& name, MAV_TYPE vehicleType) +{ + PX4ParameterMetaData* px4MetaData = qobject_cast(parameterMetaData); + + if (px4MetaData) { + return px4MetaData->getMetaDataForFact(name, vehicleType); + } else { + qWarning() << "Internal error: pointer passed to PX4FirmwarePlugin::getMetaDataForFact not PX4ParameterMetaData"; + } + + return NULL; +} + void PX4FirmwarePlugin::addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) { PX4ParameterMetaData* px4MetaData = qobject_cast(parameterMetaData); @@ -258,6 +271,11 @@ void PX4FirmwarePlugin::addMetaDataToFact(QObject* parameterMetaData, Fact* fact } } +void PX4FirmwarePlugin::getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion) +{ + return PX4ParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); +} + QList PX4FirmwarePlugin::supportedMissionCommands(void) { QList list; @@ -571,5 +589,3 @@ QGCCameraControl* PX4FirmwarePlugin::createCameraControl(const mavlink_camera_in { return new QGCCameraControl(info, vehicle, compID, parent); } - - diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h index c0fdb450c..0df75a1d5 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h @@ -56,10 +56,11 @@ public: void initializeVehicle (Vehicle* vehicle) override; bool sendHomePositionToVehicle (void) override; void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) override; + FactMetaData* getMetaDataForFact (QObject* parameterMetaData, const QString& name, MAV_TYPE vehicleType) override; QString missionCommandOverrides (MAV_TYPE vehicleType) const override; QString getVersionParam (void) override { return QString("SYS_PARAM_VER"); } QString internalParameterMetaDataFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QString(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"); } - void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) override { PX4ParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); } + void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) override; QObject* loadParameterMetaData (const QString& metaDataFile) final; bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) override; QString offlineEditingParamFile(Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/PX4/PX4.OfflineEditing.params"); } diff --git a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc index 61719557c..58dbda12e 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc +++ b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc @@ -186,6 +186,20 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData category = QStringLiteral("Standard"); } + bool volatileValue = false; + bool readOnly = false; + QString volatileStr = xml.attributes().value("volatile").toString(); + if (volatileStr.compare(QStringLiteral("true")) == 0) { + volatileValue = true; + readOnly = true; + } + if (!volatileValue) { + QString readOnlyStr = xml.attributes().value("readonly").toString(); + if (readOnlyStr.compare(QStringLiteral("true")) == 0) { + readOnly = true; + } + } + qCDebug(PX4ParameterMetaDataLog) << "Found parameter name:" << name << " type:" << type << " default:" << strDefault; // Convert type from string to FactMetaData::ValueType_t @@ -211,6 +225,8 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData metaData->setName(name); metaData->setCategory(category); metaData->setGroup(factGroup); + metaData->setReadOnly(readOnly); + metaData->setVolatileValue(volatileValue); if (xml.attributes().hasAttribute("default") && !strDefault.isEmpty()) { QVariant varDefault; @@ -387,6 +403,17 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData } } +FactMetaData* PX4ParameterMetaData::getMetaDataForFact(const QString& name, MAV_TYPE vehicleType) +{ + Q_UNUSED(vehicleType) + + if (_mapParameterName2FactMetaData.contains(name)) { + return _mapParameterName2FactMetaData[name]; + } else { + return NULL; + } +} + void PX4ParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) { Q_UNUSED(vehicleType) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h index 80c7357d8..e9c2bf0bb 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h +++ b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h @@ -33,8 +33,9 @@ class PX4ParameterMetaData : public QObject public: PX4ParameterMetaData(void); - void loadParameterFactMetaDataFile (const QString& metaDataFile); - void addMetaDataToFact (Fact* fact, MAV_TYPE vehicleType); + void loadParameterFactMetaDataFile (const QString& metaDataFile); + FactMetaData* getMetaDataForFact (const QString& name, MAV_TYPE vehicleType); + void addMetaDataToFact (Fact* fact, MAV_TYPE vehicleType); static void getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion); -- 2.22.0